diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 000000000..c88e27595 --- /dev/null +++ b/.gitattributes @@ -0,0 +1,3 @@ +# Denote all files that are truly binary and should not be modified. +*.bin binary +*.svg binary diff --git a/.gitignore b/.gitignore index f5ade5226..79868ed81 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,6 @@ build-doc/ .vscode/ int/ .idea/ +.vs/ + +src/mip/mip_version.h diff --git a/CHANGELOG.md b/CHANGELOG.md index 6b32c8ac5..836aaa4e8 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,27 +1,91 @@ - -MIP SDK Change Log -================== - -The version number scheme for the MIP SDK is MAJOR.MINOR.PATCH. - -* The MAJOR number is incremented when breaking changes are made which are not backwards compatible. - This includes public API changes and especially behavioral changes. It is likely that existing code - will not work properly and/or may not compile without changes. -* The MINOR number is incremented when a new feature is added or a current feature is improved. - Minor revisions may incorporate bug fixes and other patches. -* The PATCH number is incremented when a bug is fixed or a small, non-breaking change is made. - Patches will not significantly affect the behavior of existing code, except where such behavior - is unintentional or erroneous. - -Major revisions will specify what caused the non-backwards compatible change. These will be specified like so: -CHANGED - A non-backwards compatible change was made to an existing function/class. -RENAMED - A function/class has been renamed. -REMOVED - A function/class has been removed. - -Forthcoming ------------ -* TBD - -v1.0.0 ------- -* Initial release of the MIP SDK + +MIP SDK Change Log +================== + +The version number scheme for the MIP SDK is MAJOR.MINOR.PATCH. + +* The MAJOR number is incremented when breaking changes are made which are not backwards compatible. + This includes public API changes and especially behavioral changes. It is likely that existing code + will not work properly and/or may not compile without changes. +* The MINOR number is incremented when a new feature is added or a current feature is improved. + Minor revisions may incorporate bug fixes and other patches. +* The PATCH number is incremented when a bug is fixed or a small, non-breaking change is made. + Patches will not significantly affect the behavior of existing code, except where such behavior + is unintentional or erroneous. + +Major revisions will specify what caused the non-backwards compatible change. These will be specified like so: +CHANGED - A non-backwards compatible change was made to an existing function/class. +RENAMED - A function/class has been renamed. +REMOVED - A function/class has been removed. + +Forthcoming +----------- +### New Features +### Interface Changes +### Bug Fixes + + +v2.0.0 +------ + +### New features +* CV7-INS support +* GV7-INS support +* Logging capability (`mip_logging.h`) +* Diagnostic counters in mip parser and mip interface for debugging (define `MIP_ENABLE_DIAGNOSTICS`) +* User-defined values in CmdResult +* Additional metadata in C++ command structs +* `mip::PacketBuf` - implements `mip::PacketRef` and includes a data buffer +* Extra helper utilities + * `CompositeResult` - stores a std::vector of CmdResults and associated command descriptors + * `Index` - Helps prevent off-by-one errors when using 1-based MIP and 0-based arrays + * `RecordingConnection` - Intermediate connection which logs sent/received data to files + +### Interface Changes + +#### Renamed +* CMake: + * `WITH_SERIAL` → `MIP_USE_SERIAL` + * `WITH_TCP` → `MIP_USE_TCP` +* C++ + * `mip::Packet` → `mip::PacketRef` + * `CMD_GPS_TIME_BROADCAST_NEW` → `CMD_GPS_TIME_UPDATE` +* C + * `timestamp_type` → `mip_timestamp` + * `timeout_type` → `mip_timeout` + * `renaming_count` → `int` (typedef removed) + * `packet_length` → `uint_least16_t` (typedef removed) + * `MIP_CMD_DESC_BASE_GPS_TIME_BROADCAST_NEW` → `MIP_CMD_DESC_BASE_GPS_TIME_UPDATE` + +#### Changed +* The following 2 extern functions have been changed to callbacks to better support shared libraries. + Supply your callbacks to `mip_interface_init`. + * `mip_interface_user_send_to_device` + * `mip_interface_user_recv_from_device` +* The interface for certain commands from files in `mip/definitions` have been modified: + * Vectors and Quaternions are now explicitly-defined types. + * In C, these are typedef'd to arrays. + * In C++, these are simple structs offering conversion to/from plain arrays and some + other helpful features such as `fill`. + * Command/response structs (e.g. `mip::commands_base::DeviceDescriptors::Response`) now have + arrays embedded rather than pointers. This change simplifies user code and reduces bugs due + to dangling pointers. +* The C standard in CMake has been switched to `C11` from `C99` to reflect actual usage and fix + some warnings. +* `serial_port_init` must now be called before any of the other serial port functions. + +### Bug Fixes +* Use `NULL` payload for `mip_field_from_header_ptr` if input field isn't long enough +* Properly de-queue pending commands in `mip_interface_wait_for_reply` if `mip_interface_update` fails. +* `mip_packet_cancel_last_field` now computes the new header length correctly +* Serial Ports + * Serial ports now close themselves properly if an error occurs while reading from the port. This happens when the device is connected via USB and is unplugged. + * The port is now opened exclusively in Posix (Linux, Mac) systems + * The port is now closed properly if setup fails during `serial_port_open`. + * Removed `handle->is_open` member to avoid it becoming out of date. +* TCP connections are now supported on Windows. + + +v1.0.0 +------ +* Initial release of the MIP SDK diff --git a/CMakeLists.txt b/CMakeLists.txt index e1261efd2..c0d38f499 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) -set(CMAKE_C_STANDARD 99) +set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) project( @@ -13,18 +13,38 @@ project( LANGUAGES C CXX ) +# +# 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) +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(EXT_DIR "${CMAKE_CURRENT_LIST_DIR}/ext") - -include_directories( - "${SRC_DIR}" -) +set(MIP_CMAKE_DIR "${CMAKE_CURRENT_LIST_DIR}/cmake") if(WITH_INTERNAL) - set(MIP_INTERNAL_DIR "int" CACHE PATH "") - if(MIP_INTERNAL_DIR) - add_subdirectory("${MIP_INTERNAL_DIR}" "${CMAKE_CURRENT_BINARY_DIR}/mip-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() set(MIP_DIR "${SRC_DIR}/mip") @@ -53,16 +73,26 @@ else() endif() endif() -# -# Build options -# - -option(WITH_SERIAL "Build serial connection support into the library and examples" ON) -option(WITH_TCP "Build TCP connection support into the library and exampels" ON) - -set(MIP_TIMESTAMP_TYPE "" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") +# 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) +endif() -option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) +# 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") +configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # # Utils @@ -82,6 +112,7 @@ set(UTILS_SOURCES # set(MIP_SOURCES + "${VERSION_OUT_FILE}" "${MIP_DIR}/mip_cmdqueue.c" "${MIP_DIR}/mip_cmdqueue.h" "${MIP_DIR}/mip_dispatch.c" @@ -96,10 +127,13 @@ set(MIP_SOURCES "${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 @@ -120,6 +154,8 @@ set(MIPDEF_SOURCES "${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" @@ -135,10 +171,10 @@ set(MIPDEF_SOURCES ${INTDEF_SOURCES} ) -string(REPLACE ".h" ".hpp" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") -string(REPLACE ".c" ".cpp" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") +string(REGEX REPLACE "\.h(;|$)" ".hpp\\1" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") +string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") -if(WITH_SERIAL) +if(MIP_USE_SERIAL) list(APPEND UTILS_SOURCES "${UTILS_DIR}/serial_port.c" "${UTILS_DIR}/serial_port.h" @@ -148,7 +184,7 @@ if(WITH_SERIAL) "${MIP_DIR}/platform/serial_connection.cpp" ) endif() -if(WITH_TCP) +if(MIP_USE_TCP) list(APPEND UTILS_SOURCES "${UTILS_DIR}/tcp_socket.c" "${UTILS_DIR}/tcp_socket.h" @@ -158,6 +194,30 @@ if(WITH_TCP) "${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") + 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() + +# 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} @@ -167,25 +227,46 @@ set(ALL_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}) +target_include_directories(mip PUBLIC + "$" # Include directory for build only + "$" # Include directory for installation +) + +if(WITH_INTERNAL) + target_include_directories(mip PUBLIC + "$" + ) +endif() + +# +# Preprocessor definitions +# + +if(${MIP_LOGGING_MAX_LEVEL}) + list(APPEND MIP_DEFINES "MIP_LOGGING_MAX_LEVEL=${MIP_LOGGING_MAX_LEVEL}") +endif() if(${MIP_TIMESTAMP_TYPE}) - add_compile_definitions("MIP_TIMESTAMP_TYPE=${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) - target_compile_definitions(mip PUBLIC "NOMINMAX=1") + list(APPEND MIP_DEFINES "NOMINMAX=1" "_WIN32_WINNT=0x0501") endif() if(MSVC) @@ -194,12 +275,18 @@ else() target_compile_options(mip PRIVATE -Wall -Wextra) endif() +target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") + # -# TESTING +# Libraries # +if(WIN32 AND MIP_USE_TCP) + target_link_libraries(mip PUBLIC "ws2_32") +endif() -# CTest defines this option to ON by default, so override it to OFF here. -option(BUILD_TESTING "Build the testing tree." OFF) +# +# TESTING +# include(CTest) @@ -211,8 +298,6 @@ endif() # EXAMPLES # -option(BUILD_EXAMPLES "Builds the example programs." ON) - if(BUILD_EXAMPLES) add_subdirectory("examples") endif() @@ -222,15 +307,14 @@ endif() # find_package(Doxygen) -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) 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_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/documentation") set(DOXYGEN_IMAGE_PATH "${CMAKE_CURRENT_LIST_DIR}/docs") @@ -294,12 +378,23 @@ write_basic_package_version_file( # Installation # -install(DIRECTORY - "${SRC_DIR}/mip" - DESTINATION "${CMAKE_INSTALL_INCLUDEDIR}" - COMPONENT mip - FILES_MATCHING PATTERN "*.h*" -) +# 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 @@ -400,9 +495,7 @@ if(BUILD_PACKAGE) set(CPACK_PACKAGE_CONTACT "Rob Fisher ") set(CPACK_COMPONENTS_ALL "mip") - # Massage the version number a little so we can set the proper version - string(REGEX REPLACE "^v([0-9]+)\\.([0-9]+)\\.([0-9]+).*" "\\1.\\2.\\3" MIP_GIT_VERSION_CPACK ${MIP_GIT_VERSION}) - set(CPACK_PACKAGE_VERSION ${MIP_GIT_VERSION_CPACK}) + set(CPACK_PACKAGE_VERSION ${MIP_GIT_VERSION_CLEAN}) # Shared configuration set(MIP_FILE_NAME_PREFIX "mipsdk_${MIP_GIT_VERSION}_${MIP_ARCH}") @@ -421,8 +514,8 @@ if(BUILD_PACKAGE) # Zip specific configuration # Build different zip packages for each target - if(WIN32) - set(CPACK_ARCHIVE_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}_Windows") + if(MSVC) + set(CPACK_ARCHIVE_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}_MSVC_v${MSVC_TOOLSET_VERSION}") elseif(APPLE) set(CPACK_ARCHIVE_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}_OSX") elseif(UNIX) diff --git a/Jenkinsfile b/Jenkinsfile index f3b6b125f..db84d00c3 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -17,7 +17,7 @@ def checkoutRepo() { branches: [ [name: 'refs/heads/' + BRANCH_NAME_REAL] ], - userRemoteConfigs: [[credentialsId: 'ffc94480-3383-4390-82e6-af2fb5e6c76d', url: 'https://github.com/LORD-MicroStrain/libmip.git']], + userRemoteConfigs: [[credentialsId: 'Github_User_And_Token', url: 'https://github.com/LORD-MicroStrain/libmip.git']], extensions: [ ] ]) @@ -39,6 +39,7 @@ pipeline { cd build_Win32 cmake .. ` -A "Win32" ` + -T "v142" ` -DBUILD_DOCUMENTATION=ON ` -DBUILD_PACKAGE=ON cmake --build . -j @@ -58,6 +59,7 @@ pipeline { cd build_x64 cmake .. ` -A "x64" ` + -T "v142" ` -DBUILD_PACKAGE=ON cmake --build . -j cmake --build . --target package @@ -70,7 +72,6 @@ pipeline { options { skipDefaultCheckout() } steps { checkoutRepo() - sh "cp /etc/pki/ca-trust/source/anchors/ZScaler.crt ./.devcontainer/extra_cas/" sh "./.devcontainer/docker_build.sh --os ubuntu --arch amd64" archiveArtifacts artifacts: 'build_ubuntu_amd64/mipsdk_*' } @@ -80,11 +81,28 @@ pipeline { options { skipDefaultCheckout() } steps { checkoutRepo() - sh "cp /etc/pki/ca-trust/source/anchors/ZScaler.crt ./.devcontainer/extra_cas/" 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_*' + // } + // } } } } @@ -93,78 +111,40 @@ pipeline { script { if (BRANCH_NAME && BRANCH_NAME == 'develop') { node("linux-amd64") { - withCredentials([string(credentialsId: 'MICROSTRAIN_BUILD_GH_TOKEN', variable: 'GH_TOKEN')]) { - sh ''' - release_name="latest" - repo="LORD-MicroStrain/libmip" - archive_dir="${WORKSPACE}/../builds/${BUILD_NUMBER}/archive/" - artifacts=$(find "${archive_dir}" -type f) - gh release delete \ - -y \ - -R "${repo}" \ - "${release_name}" || echo "No existing release named ${release_name}" - gh release create \ - -R "${repo}" \ - --title "${release_name}" \ - --target "${BRANCH_NAME}" \ - --generate-notes \ - "${release_name}" ${artifacts} - - # Commit the documentation to the github pages branch - export GIT_ASKPASS="${HOME}/.git-askpass" - docs_zip=$(find "${archive_dir}" -type f -name "mipsdk_*_Documentation.zip" | sort | uniq) - docs_dir="${WORKSPACE}/mip_sdk_documentation/${release_name}" - git clone -b "main" "https://github.com/LORD-MicroStrain/mip_sdk_documentation.git" mip_sdk_documentation - rm -rf "${docs_dir}" - mkdir -p "${docs_dir}" - pushd "${docs_dir}" - unzip "${docs_zip}" -d "${docs_dir}" - git add --all - git commit -m "Adds documentation for ${release_name}" - git push origin main - popd - ''' + dir("/tmp/mip_sdk_${env.BRANCH_NAME}_${currentBuild.number}") { + copyArtifacts(projectName: "${env.JOB_NAME}", selector: specific("${currentBuild.number}")); + withCredentials([string(credentialsId: 'Github_Token', variable: 'GH_TOKEN')]) { + sh ''' + # Release to github + "${WORKSPACE}/scripts/release.sh" \ + --artifacts "$(find "$(pwd)" -type f)" \ + --target "${BRANCH_NAME}" \ + --release "latest" \ + --docs-zip "$(find "$(pwd)" -type f -name "mipsdk_*_Documentation.zip" | sort | uniq)" \ + --generate-notes + ''' + } } } } else if (BRANCH_NAME && BRANCH_NAME == 'master') { node("linux-amd64") { - withCredentials([string(credentialsId: 'MICROSTRAIN_BUILD_GH_TOKEN', variable: 'GH_TOKEN')]) { - sh ''' - # Release to the latest version if the master commit matches up with the commit of that version - repo="LORD-MicroStrain/libmip" - archive_dir="${WORKSPACE}/../builds/${BUILD_NUMBER}/archive/" - artifacts=$(find "${archive_dir}" -type f) - if git describe --exact-match --tags HEAD &> /dev/null; then - # Deploy the artifacts to Github - tag=$(git describe --exact-match --tags HEAD) - gh release delete \ - -y \ - -R "${repo}" \ - "${tag}" || echo "No existing release named ${tag}" - gh release create \ - -R "${repo}" \ - --title "${tag}" \ - --target "${BRANCH_NAME}" \ - --notes "" \ - "${tag}" ${artifacts} - - # Commit the documentation to the github pages branch - export GIT_ASKPASS="${HOME}/.git-askpass" - docs_zip=$(find "${archive_dir}" -type f -name "mipsdk_*_Documentation.zip" | sort | uniq) - docs_dir="${WORKSPACE}/mip_sdk_documentation/${tag}" - git clone -b "main" "https://github.com/LORD-MicroStrain/mip_sdk_documentation.git" mip_sdk_documentation - rm -rf "${docs_dir}" - mkdir -p "${docs_dir}" - pushd "${docs_dir}" - unzip "${docs_zip}" -d "${docs_dir}" - git add --all - git commit -m "Adds documentation for ${tag}" - git push origin main - popd - else - echo "Not releasing from ${BRANCH_NAME} since the current commit does not match the latest released version commit" - fi - ''' + dir("/tmp/mip_sdk_${env.BRANCH_NAME}_${currentBuild.number}") { + copyArtifacts(projectName: "${env.JOB_NAME}", selector: specific("${currentBuild.number}")); + withCredentials([string(credentialsId: 'MICROSTRAIN_BUILD_GH_TOKEN', variable: 'GH_TOKEN')]) { + sh ''' + # 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 \ + --artifacts "$(find "$(pwd)" -type f)" \ + --target "${BRANCH_NAME}" \ + --release "$(cd ${WORKSPACE} && git describe --exact-match --tags HEAD)" \ + --docs-zip "$(find "$(pwd)" -type f -name "mipsdk_*_Documentation.zip" | sort | uniq)" + else + echo "Not releasing from ${BRANCH_NAME} since the current commit does not match the latest released version commit" + fi + ''' + } } } } diff --git a/LICENSE.txt b/LICENSE.txt index c14e75f11..578555ed7 100644 --- a/LICENSE.txt +++ b/LICENSE.txt @@ -1,21 +1,21 @@ -The MIT License (MIT) - -Copyright(c) 2022 Parker Hannifin Corp. All rights reserved. - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +The MIT License (MIT) + +Copyright(c) 2022 Parker Hannifin Corp. All rights reserved. + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. \ No newline at end of file diff --git a/README.md b/README.md index a2082bb9e..1edc92919 100644 --- a/README.md +++ b/README.md @@ -14,9 +14,9 @@ Features * No dependence on any RTOS or threading * Simple to interface with existing projects * FindMip.cmake is included for CMake-based projects -* Can be used to parse offline binary files -* C API for those who can't use C++ +* It can be used to parse offline binary files * C++ API for safety, flexibility, and convenience. +* C API for those who can't use C++ * Advanced Features * MIP packet creation @@ -26,14 +26,22 @@ Features Examples -------- -* Get device information [C++] - queries the device strings and prints them to stdout. -* Watch IMU [C, C++] - Configures the IMU for streaming and prints the data to stdout. + +* 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, C++] - Configures the device for typical usage in a wheeled-vehicle application. - * CV7 setup [C, C++] - Configures the device for typical usage and includes an example of using the event system. - * GX5-45 setup [C, C++] - Configures the device for typical usage in a wheeled-vehicle application. + * 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)] -You'll need to enable at least one of the communications interfaces in the CMake configuration (see below) to use the examples. +You'll need to enable at least one of the [communications interfaces](#communications-interfaces) in the CMake configuration to use the examples. The examples take two parameters for the device connection: * For a serial connection: Port and baudrate. Port must start with `/dev/` on Linux or `COM` on Windows. @@ -43,7 +51,38 @@ The examples take two parameters for the device connection: Documentation ------------- -https://lord-microstrain.github.io/mip_sdk_documentation/latest/index.html +Documentation for all released versions can be found [here](https://lord-microstrain.github.io/mip_sdk_documentation). + +### C and C++ APIs + +The C++ API is implemented on top of the C API to provide additional features: +* Object-oriented interfaces +* Improved type safety and sanity checking +* Better clarity / reduced verbosity (e.g. with `using namespace mip`) + +The C++ API uses `TitleCase` for types and `camelCase` for functions and variables, while the C api uses `snake_case` naming for +everything. This makes it easy to tell which is being used when looking at the examples. + +The C API can be accessed directly from C++ via the `mip::C` namespace. + +### Command Results + +MIP devices return an ack/nack field in response to commands to allow the user to determine if the command was +successfully executed. These fields contain a "reply code" which is defined by the MIP protocol. This library +additionally defines several "status codes" for situations where an ack/nack field is not applicable (i.e. if +the device doesn't respond to the command, if the command couldn't be transmitted, etc). + +See the documentation page for [Command Results](https://lord-microstrain.github.io/mip_sdk_documentation/latest/command_results.html) for details. + +### Timestamps + +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 +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). Communications Interfaces @@ -53,19 +92,19 @@ Two connection types are provided with the MIP SDK to make it easy to run the ex ### Serial Port -A basic serial port interface is provided in C and C++ for Linux and Windows. These can be modified for other platforms by the user. +A basic serial port interface is provided in C and C++ for Linux, Mac, and Windows. These can be modified for other platforms by the user. 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 in the CMake configuration with `-DWITH_SERIAL=1`. +[Enable it](#build-configuration) in the CMake configuration with `-DMIP_USE_SERIAL=1`. ### TCP Client The TCP client connection allows you to connect to a MIP device remotely. The MIP device must be connected -via the normal serial or USB cable to a commputer system running a TCP server which forwards data between +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 in the CMake configuration with `-DWITH_TCP=1`. +[Enable it](#build-configuration) in the CMake configuration with `-DMIP_USE_TCP=1`. How to Build @@ -73,20 +112,24 @@ How to Build ### Prerequisites -* CMake version 3.10 or later * A working C compiler - * C99 or later required + * 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++. * 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) +* CMake version 3.10 or later (technically this is optional, see below) * Doxygen, if building documentation -### Build configuration +### CMake Build Configuration The following options may be specified when configuring the build with CMake (e.g. `cmake .. -DOPTION=VALUE`): -* WITH_SERIAL - Builds the included serial port library (default enabled). -* WITH_TCP - Builds the included socket library (default enabled). +* 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. +* 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. @@ -94,81 +137,46 @@ The following options may be specified when configuring the build with CMake (e. * 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 with CMake +### Compilation 1. Create the build directory (e.g. `mkdir build`). 2. In the build directory, run `cmake .. ` - * Replace `` with your configuration options, such as `-DWITH_SERIAL=1`. + * Replace `` with your configuration options, such as `-DMIP_USE_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 ` + * 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. +### Building without CMake -Implementation Notes --------------------- +If your target platform doesn't support CMake, you can build the project without it. To do so, +include all the necessary files and define a few options. -### User-Implemented Functions +#### 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. -There are two C functions which must be implemented to use this library. +#### Required #defines for building without CMake -The first, `mip_interface_user_recv_from_device()`, must fetch raw data bytes from the connected MIP device. Typically this means reading from -a serial port or TCP socket. +Pass these to your compiler as appropriate, e.g. `arm-none-eabi-gcc -DMIP_TIMESTAMP_TYPE=uint32_t -DMIP_ENABLE_LOGGING=0` -The second, `mip_interface_send_to_device()`, must pass the provided data bytes directly to the connected MIP device. +* MIP_ENABLE_LOGGING (and MIP_LOGGING_MAX_LEVEL) - default is enabled +* MIP_TIMESTAMP_TYPE - defaults to uint64_t if not specified +* MIP_ENABLE_DIAGNOSTICS - Supported on embedded platforms to aid debugging -See https://lord-microstrain.github.io/mip_sdk_documentation/latest/mip_interface.html for details on how to implement these functions. +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 +headers from the MIP SDK. (If you change them after building, make sure everything gets +rebuilt properly. Normally CMake takes care of this for you). -#### C++ -For C++ applications, these functions are implemented by the `MipDeviceInterface` class, which takes a `Connection` object responsible -for reading and writing to the device. Create a class derived from `Connection` and implement the pure virtual `recvFromDevice` and -`sendToDevice` methods. - -If you do not wish to use the `MipDeviceInterface` class, do not compile the corresponding source file and create the -C functions yourself. Declare them functions as `extern "C"` to avoid linking problems between the C and C++ code. - -### Command Results (mip_cmd_result / MipCmdResult) - -Command results are divided into two categories: -* Reply codes are returned by the device, e.g.: - * ACK / OK - * Invalid parameter - * Unknown command -* Status codes are set by this library, e.g.: - * General ERROR - * TIMEDOUT - * Other statuses are used while the command is still in process - -### Timestamps and Timeouts - -Timestamps (`timestamp_type` / `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 poxis `time()` function or from the -`std::chrono` library. On ARM systems, it is often derived from the Systick timer. - -By default, timestamps are `typedef`'d to `uint32_t` and are typically in milliseconds. 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` instead. - -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. - -### C and C++ APIs - -The C++ API is implemented on top of the C API to provide additional features: -* Object-oriented interfaces -* Improved type safety and sanity checking -* Better clarity / reduced verbosity (e.g. with `using namespace mip`) +Known Issues +------------ -The C++ API uses `TitleCase` for types and `camelCase` for functions and variables, while the C api uses `snake_case` naming for -everything. This makes it easy to tell which is being used when looking at the examples. +* `suppress_ack=true` is not supported +* The commanded BIT, device settings, and capture gyro bias commands can time out unless the timeout is increased -The C API can be accessed directly from C++ via the `mip::C` namesace. +See the documentation page for [Known Issues](https://lord-microstrain.github.io/mip_sdk_documentation/latest/other.html#known_issues). diff --git a/cmake/mip_version.h.in b/cmake/mip_version.h.in new file mode 100644 index 000000000..95cdf4df6 --- /dev/null +++ b/cmake/mip_version.h.in @@ -0,0 +1,10 @@ +#pragma once + +// Full version of the MIP SDK including a git commit hash if this build was not built on a tag +#define MIP_SDK_VERSION_FULL "${MIP_GIT_VERSION}" + +// Semantic version information of the MIP SDK +#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 diff --git a/docs/docs.c b/docs/docs.c index eb80cd4a4..82cba0c54 100644 --- a/docs/docs.c +++ b/docs/docs.c @@ -1,8 +1,10 @@ //////////////////////////////////////////////////////////////////////////////// ///@mainpage MIP SDK /// -/// Welcome to the official MIP Software Development Kit. -/// +/// 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 /// @@ -15,17 +17,17 @@ ///@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) /// -/// See @ref mip_interface for details on how to get started. -/// ///@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::DeviceInterface Top-level MIP interface class. -///@li @ref mip::Packet A class representing a MIP packet for either transmission or reception. -///@li @ref mip::Field A class representing a MIP field within a packet. +///@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. /// ///@section quickref_c Quick Reference [C] /// @@ -38,12 +40,16 @@ ///@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: @@ -57,17 +63,20 @@ /// will return a status code. /// /// Sending and receiving to or from the device occurs via two functions: -///@li mip_interface_user_send_to_device() for transmission and -///@li mip_interface_user_recv_from_device() for reception. +///@li mip::DeviceInterface::sendToDevice() or +/// mip_interface_send_to_device() for transmission and +///@li mip::DeviceInterface::recvFromDevice() or +/// mip_interface_recv_from_device() for reception. /// -/// The application must define these two C functions, or subclass -/// mip::DeviceInterface and implement the pure virtual functions. -/// This should be straightforward; simply pass the bytes between the MIP -/// interface and the connection. +/// 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. /// -/// Because the device transmits continuously when streaming data, the -/// application must poll the connection for new data frequently. This is -/// done via the @ref update "update function". +///@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: @@ -83,14 +92,19 @@ ///@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 most -/// cases, applications will call a single function for each needed command. +/// 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. When reading from the device, -/// these commands will also report the device response information, assuming -/// the command was successful. The command functions are blocking, that is, -/// they halt execution until the device responds or the command times out. +/// 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 @@ -118,7 +132,7 @@ ///@par Packet callbacks /// ///@code{.cpp} -/// void packet_callback(void* userdata, const Packet& packet, Timestamp parseTime) +/// void packet_callback(void* userdata, const mip::PacketRef& packet, Timestamp parseTime) ///@endcode /// /// Packet callbacks are invoked when a packet is received which matches the @@ -135,7 +149,7 @@ ///@par Field callbacks /// ///@code{.cpp} -/// void field_callback(void* userdata, const Field& field, Timestamp parseTime) +/// void field_callback(void* userdata, const mip::Field& field, Timestamp parseTime) ///@endcode /// /// Similar to packet callbacks, field callbacks are invoked when a MIP @@ -153,7 +167,7 @@ ///@par Data callbacks /// ///@code{.cpp} -/// void data_callback(void* userdata, const data_sensor::ScaledAccel& packet, Timestamp parseTime) +/// 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 @@ -161,6 +175,7 @@ /// 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 @@ -176,13 +191,13 @@ /// /// The application should call mip_interface_update() periodically to process /// data sent by the device. This update function will call -/// mip_interface_user_recv_from_device() to parse packets. When a data packet is +/// 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_write_message_format() / mip::writeMessageFormat()) +/// 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 @@ -195,7 +210,7 @@ /// 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_user_recv_from_device(). Because the function is called from +/// 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. @@ -254,10 +269,9 @@ /// ///@par Other thread-safety concerns /// -///@li Data transmission to the device (for sending commands) is thread-safe +///@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 mip_interface_user_send_to_device() is -/// thread-safe (e.g. by using a mutex). +/// 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 @@ -269,10 +283,10 @@ /// 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_user_recv_from_device() when +///@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_user_recv_from_device()) +/// 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. @@ -359,13 +373,13 @@ /// 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 transfered well within the transmission time plus +/// 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 timestamp_type +///@see mip_timestamp ///@see mip::Timestamp /// //////////////////////////////////////////////////////////////////////////////// @@ -410,4 +424,120 @@ /// 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::DeviceInterface::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/examples/CMakeLists.txt b/examples/CMakeLists.txt index 033973966..b641684d5 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -3,60 +3,101 @@ set(EXAMPLE_DIR "${CMAKE_CURRENT_LIST_DIR}") set(DEVICE_SOURCES + "${EXAMPLE_DIR}/example_utils.c" + "${EXAMPLE_DIR}/example_utils.h" "${EXAMPLE_DIR}/example_utils.cpp" "${EXAMPLE_DIR}/example_utils.hpp" ) -if(WITH_SERIAL) +if(MIP_USE_SERIAL) set(SERIAL_DEFS "MIP_USE_SERIAL") endif() -if(WITH_TCP) +if(MIP_USE_TCP) set(TCP_DEFS "MIP_USE_TCP") endif() +if(MIP_USE_EXTRAS) + set(EXTRAS_DEFS "MIP_USE_EXTRAS") +endif() + +set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) -if(WITH_SERIAL OR WITH_TCP) +# 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 "${SERIAL_DEFS}" "${TCP_DEFS}") + target_compile_definitions(DeviceInfo PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(DeviceInfo PUBLIC "${EXAMPLE_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 "${SERIAL_DEFS}" "${TCP_DEFS}") + target_compile_definitions(WatchImu PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(WatchImu PUBLIC "${EXAMPLE_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 "${SERIAL_DEFS}" "${TCP_DEFS}") + target_compile_definitions(ThreadingDemo PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(ThreadingDemo PUBLIC "${EXAMPLE_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 "${SERIAL_DEFS}" "${TCP_DEFS}") + target_compile_definitions(GQ7_Example PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(GQ7_Example PUBLIC "${EXAMPLE_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 "${SERIAL_DEFS}" "${TCP_DEFS}") + target_compile_definitions(CV7_Example PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(CV7_Example PUBLIC "${EXAMPLE_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 PUBLIC "${EXAMPLE_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 PUBLIC "${EXAMPLE_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 "${SERIAL_DEFS}" "${TCP_DEFS}") + add_executable(CX5_GX5_45_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.cpp" ${DEVICE_SOURCES}) + target_link_libraries(CX5_GX5_45_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") + target_compile_definitions(CX5_GX5_45_Example PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(CX5_GX5_45_Example PUBLIC "${EXAMPLE_DIR}") + + add_executable(CX5_GX5_CV5_15_25_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp" ${DEVICE_SOURCES}) + target_link_libraries(CX5_GX5_CV5_15_25_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") + target_compile_definitions(CX5_GX5_CV5_15_25_Example PUBLIC "${SERIAL_DEFS}" "${TCP_DEFS}") + target_include_directories(CX5_GX5_CV5_15_25_Example PUBLIC "${EXAMPLE_DIR}") endif() - add_executable(WatchImuC "${EXAMPLE_DIR}/watch_imu.c") +endif() + +# C examples need serial support +if(MIP_USE_SERIAL) + add_executable(WatchImuC "${EXAMPLE_DIR}/watch_imu.c" ${DEVICE_SOURCES}) target_link_libraries(WatchImuC mip) + target_include_directories(WatchImuC PUBLIC "${EXAMPLE_DIR}") - add_executable(GQ7_ExampleC "${EXAMPLE_DIR}/GQ7/GQ7_example.c") + add_executable(GQ7_ExampleC "${EXAMPLE_DIR}/GQ7/GQ7_example.c" ${DEVICE_SOURCES}) target_link_libraries(GQ7_ExampleC mip) + target_include_directories(GQ7_ExampleC PUBLIC "${EXAMPLE_DIR}") - add_executable(CV7_ExampleC "${EXAMPLE_DIR}/CV7/CV7_example.c") + add_executable(CV7_ExampleC "${EXAMPLE_DIR}/CV7/CV7_example.c" ${DEVICE_SOURCES}) target_link_libraries(CV7_ExampleC mip) + target_include_directories(CV7_ExampleC PUBLIC "${EXAMPLE_DIR}") + + add_executable(CX5_GX5_45_ExampleC "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.c" ${DEVICE_SOURCES}) + target_link_libraries(CX5_GX5_45_ExampleC mip) + target_include_directories(CX5_GX5_45_ExampleC PUBLIC "${EXAMPLE_DIR}") - add_executable(GX5_45_ExampleC "${EXAMPLE_DIR}/GX5_45/GX5_45_example.c") - target_link_libraries(GX5_45_ExampleC mip) + add_executable(CX5_GX5_CV5_15_25_ExampleC "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c" ${DEVICE_SOURCES}) + target_link_libraries(CX5_GX5_CV5_15_25_ExampleC mip) + target_include_directories(CX5_GX5_CV5_15_25_ExampleC PUBLIC "${EXAMPLE_DIR}") endif() diff --git a/examples/CV7/CV7_example.c b/examples/CV7/CV7_example.c index 30366d804..b84c7167b 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, PARKER MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN 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. @@ -31,9 +31,9 @@ #include #include #include -#include #include +#include "example_utils.h" //////////////////////////////////////////////////////////////////////////////// // Global Variables @@ -71,9 +71,9 @@ const uint8_t FILTER_PITCH_EVENT_ACTION_ID = 2; //Required MIP interface user-defined functions -timestamp_type get_current_timestamp(); +mip_timestamp get_current_timestamp(); -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, size_t* out_length, timestamp_type* 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); bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length); int usage(const char* argv0); @@ -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, timestamp_type timestamp); +void handle_filter_event_source(void* user, const mip_field* field, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// @@ -125,7 +125,10 @@ int main(int argc, const char* argv[]) //Initialize the MIP interface // - mip_interface_init(&device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000); + mip_interface_init( + &device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000, + &mip_interface_user_send_to_device, &mip_interface_user_recv_from_device, &mip_interface_default_update, NULL + ); // @@ -310,14 +313,17 @@ int main(int argc, const char* argv[]) //Main Loop: Update the interface and process data // - bool running = true; - timestamp_type prev_print_timestamp = 0; + bool running = true; + mip_timestamp prev_print_timestamp = 0; printf("Sensor is configured... waiting for filter to enter AHRS mode.\n"); + char *state_init = ""; + char **current_state = &state_init; while(running) { mip_interface_update(&device, false); + displayFilterState(filter_status.filter_state, current_state, false); //Check Filter State if((!filter_state_ahrs) && (filter_status.filter_state == MIP_FILTER_MODE_AHRS)) @@ -329,7 +335,7 @@ int main(int argc, const char* argv[]) //Once in full nav, print out data at 10 Hz if(filter_state_ahrs) { - timestamp_type curr_time = get_current_timestamp(); + mip_timestamp curr_time = get_current_timestamp(); if(curr_time - prev_print_timestamp >= 100) { @@ -352,7 +358,7 @@ int main(int argc, const char* argv[]) // Filter Event Source Field Handler //////////////////////////////////////////////////////////////////////////////// -void handle_filter_event_source(void* user, const mip_field* field, timestamp_type timestamp) +void handle_filter_event_source(void* user, const mip_field* field, mip_timestamp timestamp) { mip_shared_event_source_data data; @@ -370,12 +376,12 @@ void handle_filter_event_source(void* user, const mip_field* field, timestamp_ty // MIP Interface Time Access Function //////////////////////////////////////////////////////////////////////////////// -timestamp_type get_current_timestamp() +mip_timestamp get_current_timestamp() { clock_t curr_time; curr_time = clock(); - return (timestamp_type)((double)(curr_time - start_time)/(double)CLOCKS_PER_SEC*1000.0); + return (mip_timestamp)((double)(curr_time - start_time) / (double)CLOCKS_PER_SEC * 1000.0); } @@ -383,10 +389,10 @@ timestamp_type 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, size_t* out_length, timestamp_type* 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) { *timestamp_out = get_current_timestamp(); - return serial_port_read(&device_port, buffer, max_length, out_length); + return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); } diff --git a/examples/CV7/CV7_example.cpp b/examples/CV7/CV7_example.cpp index fb1cc991e..4dbb7a54c 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, PARKER MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN 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. @@ -27,9 +27,11 @@ // Include Files //////////////////////////////////////////////////////////////////////////////// +#include "example_utils.hpp" + #include + #include -#include "../example_utils.hpp" using namespace mip; @@ -76,7 +78,16 @@ void handleFilterEventSource(void*, const mip::Field& field, mip::Timestamp time int main(int argc, const char* argv[]) { - std::unique_ptr utils = handleCommonArgs(argc, 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; // @@ -264,11 +275,13 @@ int main(int argc, const char* argv[]) bool running = true; mip::Timestamp prev_print_timestamp = getCurrentTimestamp(); - printf("Sensor is configured... waiting for filter to enter AHRS mode.\n"); + printf("Sensor is configured... waiting for filter to enter AHRS mode (AHRS).\n"); + auto current_state = std::string{""}; 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)) @@ -277,7 +290,7 @@ int main(int argc, const char* argv[]) filter_state_ahrs = true; } - //Once in full nav, print out data at 10 Hz + //Once in AHRS Flter Mode, print out data at 10 Hz if(filter_state_ahrs) { mip::Timestamp curr_timestamp = getCurrentTimestamp(); @@ -338,6 +351,7 @@ void exit_gracefully(const char *message) printf("%s\n", message); #ifdef _WIN32 + 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 new file mode 100644 index 000000000..5a9177557 --- /dev/null +++ b/examples/CV7_INS/CV7_INS_simple_example.cpp @@ -0,0 +1,366 @@ +///////////////////////////////////////////////////////////////////////////// +// +// CV7_INS_simple_example.cpp +// +// C++ Example usage program for the CV7-INS +// +// This example shows the basic setup for a CV-INS sensor using external aiding measurements. +// It is not an exhaustive example of all CV7 settings. +// If your specific setup needs are not met by this example, please consult +// the MSCL-embedded API documentation for the proper commands. +// +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + + +//////////////////////////////////////////////////////////////////////////////// +// Include Files +//////////////////////////////////////////////////////////////////////////////// + +#include "mip/mip_all.hpp" +#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; + +uint8_t external_heading_sensor_id = 1; +uint8_t gnss_antenna_sensor_id = 2; +uint8_t vehicle_frame_velocity_sensor_id = 3; + +bool filter_state_full_nav = false; + +//////////////////////////////////////////////////////////////////////////////// +// Function Prototypes +//////////////////////////////////////////////////////////////////////////////// + +int usage(const char* argv0); + +void print_device_information(const commands_base::BaseDeviceInfo& device_info); + +void exit_gracefully(const char *message); +bool should_exit(); + +//////////////////////////////////////////////////////////////////////////////// +// Main Function +//////////////////////////////////////////////////////////////////////////////// + + +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; + + // + //Ping the device (note: this is good to do to make sure the device is present) + // + + if(commands_base::ping(*device) != 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) + exit_gracefully("ERROR: Failed to get device info"); + print_device_information(device_info); + + + // + //Idle the device (note: this is good to do during setup) + // + + if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not set the device to idle!"); + + + // + //Load the device default settings (so the device is in a known state) + // + + if(commands_3dm::defaultDeviceSettings(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not load default device settings!"); + + + // + //Setup external aiding sensor reference frames + // + + + // + //External heading sensor reference frame. + // + 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) + 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; + 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) + 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; + 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) + exit_gracefully("ERROR: Unable to configure external vehicle frame velocity sensor ID"); + + + // + //Setup FILTER data format + // + + uint16_t filter_base_rate; + + if(commands_3dm::getBaseRate(*device, data_filter::DESCRIPTOR_SET, &filter_base_rate) != 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 }, + }}; + + if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, filter_descriptors.size(), filter_descriptors.data()) != 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; + 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) + 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) + exit_gracefully("ERROR: Could not reset the filter!"); + + + // + // Register data callbacks + // + + //Filter Data + DispatchHandler filter_data_handlers[5]; + + device->registerExtractor(filter_data_handlers[0], &filter_gps_time, 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); + + // + //Resume the device + // + + if(commands_base::resume(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not resume the device!"); + + + // + //Main Loop: Update the interface and process data + // + + bool running = true; + mip::Timestamp prev_print_timestamp = getCurrentTimestamp(); + mip::Timestamp prev_measurement_update_timestamp = getCurrentTimestamp(); + + printf("Sensor is configured... waiting for filter to initialize (FULL_NAV)...\n"); + + std::string current_state = std::string{""}; + while(running) + { + device->update(); + 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)) + { + printf("NOTE: Filter has entered full navigation mode.\n"); + filter_state_full_nav = true; + } + + // Check that enough time has elapsed to send a new measurement update + mip::Timestamp current_timestamp = getCurrentTimestamp(); + mip::Timestamp elapsed_time_from_last_measurement_update = current_timestamp - prev_measurement_update_timestamp; + mip::Timestamp elapsed_time_from_last_message_print = current_timestamp - prev_print_timestamp; + + 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; + external_measurement_time.reserved = 1; + external_measurement_time.nanoseconds = current_timestamp * uint64_t(1000000); + + // External heading command + float external_heading = 0.0; + float external_heading_uncertainty = 0.001; + 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"); + + // External position command + double latitude = 44.43729093897896; // Lat/Lon for MicroStrain headquarters + 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) + 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}; + 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}; + 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"); + + 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)) + { + printf("\n\n****Filter navigation state****\n"); + printf("TIMESTAMP: %f\n", filter_gps_time.tow); + printf("ATTITUDE_EULER = [%f %f %f]\n", filter_euler_angles.roll, filter_euler_angles.pitch, filter_euler_angles.yaw); + printf("LLH_POSITION = [%f %f %f]\n", filter_llh_position.latitude, filter_llh_position.longitude, filter_llh_position.ellipsoid_height); + printf("NED_VELOCITY = [%f %f %f]\n", filter_ned_velocity.north, filter_ned_velocity.east, filter_ned_velocity.down); + + prev_print_timestamp = current_timestamp; + } + + running = !should_exit(); + } + + exit_gracefully("Example Completed Successfully."); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Print device information +//////////////////////////////////////////////////////////////////////////////// + +void print_device_information(const commands_base::BaseDeviceInfo& device_info) +{ + printf("Connected to:\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: ", device_info.model_name); + print_info("Model number: ", device_info.model_number); + print_info("Serial Number: ", device_info.serial_number); + print_info("Device Options: ", device_info.device_options); + print_info("Lot Number: ", device_info.lot_number); + + printf( " Firmware version: %d.%d.%d\n\n", + (device_info.firmware_version / 1000), + (device_info.firmware_version / 100) % 10, + (device_info.firmware_version / 1) % 100 + ); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Print Usage Function +//////////////////////////////////////////////////////////////////////////////// + +int usage(const char* argv0) +{ + printf("Usage: %s \n", argv0); + return 1; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Exit Function +//////////////////////////////////////////////////////////////////////////////// + +void exit_gracefully(const char *message) +{ + if(message) + printf("%s\n", message); + +#ifdef _WIN32 + printf("Press ENTER to exit...\n"); + int dummy = getchar(); +#endif + + exit(0); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Check for Exit Condition +//////////////////////////////////////////////////////////////////////////////// + +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 new file mode 100644 index 000000000..470eaa627 --- /dev/null +++ b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp @@ -0,0 +1,517 @@ +///////////////////////////////////////////////////////////////////////////// +// +// CV7_INS_simple_ublox_example.cpp +// +// C++ Example usage program for the CV7-INS with a UBlox receiver +// +// This example shows the basic interface between the CV7-INS and a UBlox receiver preconfigured to stream a the UBX-NAV-PVT message. +// It is intended to demonstrate the relevant MIP API calls to input GNSS data to the CV7-INS +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + + +//////////////////////////////////////////////////////////////////////////////// +// Include Files +//////////////////////////////////////////////////////////////////////////////// + +#include "mip/mip_all.hpp" +#include "example_utils.hpp" +#include "ublox_device.hpp" + +#include +#include +#include +#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; + +uint8_t gnss_antenna_sensor_id = 1; + +bool filter_state_full_nav = false; + +struct InputArguments +{ + std::string mip_device_port_name; + std::string mip_device_baudrate; + std::string mip_binary_filepath; + + std::string ublox_device_port_name; + std::string ublox_device_baudrate; + + bool enable_pps_sync = false; + + int pps_input_pin_id = 1; + + commands_filter::InitializationConfiguration::AlignmentSelector filter_heading_alignment_method = commands_filter::InitializationConfiguration::AlignmentSelector::KINEMATIC; + + float gnss_antenna_lever_arm[3] = {0,0,0}; +}; + +//////////////////////////////////////////////////////////////////////////////// +// Function Prototypes +//////////////////////////////////////////////////////////////////////////////// + +int usage(const char* argv0); + +void print_device_information(const commands_base::BaseDeviceInfo& device_info); + +void exit_gracefully(const char *message); +bool should_exit(); + +InputArguments parse_input_arguments(int argc, const char* argv[]); + +uint64_t convert_gps_tow_to_nanoseconds(int week_number, float time_of_week); + +int get_gps_week(int year, int month, int day); + +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; + + // + // 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)); + + // + //Attempt to idle the device before pinging + // + 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) + 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) + exit_gracefully("ERROR: Failed to get device info"); + print_device_information(device_info); + + // + //Idle the device (note: this is good to do during setup) + // + + if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not set the device to idle!"); + + + // + //Load the device default settings (so the device is in a known state) + // + + if(commands_3dm::defaultDeviceSettings(*device) != 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; + 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) + exit_gracefully("ERROR: Unable to configure external GNSS antenna frame ID"); + + + // + // Set heading initialization source + // + + 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) + exit_gracefully("ERROR: Could not load default device settings!"); + + + if (input_arguments.enable_pps_sync) + { + + // + //Setup SYSTEM data format to monitor PPS status + // + + uint16_t system_data_base_rate; + if(commands_3dm::getBaseRate(*device, data_system::DESCRIPTOR_SET, &system_data_base_rate) != 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 }, + }}; + + if(commands_3dm::writeMessageFormat(*device, data_system::DESCRIPTOR_SET, system_data_descriptors.size(), system_data_descriptors.data()) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not set system data message format!"); + + + // + // 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) + exit_gracefully("ERROR: Could not set GPIO to PPS input!"); + + + // + // Setup PPS source as GPIO + // + + if (mip::commands_3dm::writePpsSource(*device, mip::commands_3dm::PpsSource::Source::GPIO) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Failed to set PPS source to GPIO!"); + + } + + // + //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) + 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; + 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) + 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) + exit_gracefully("ERROR: Could not reset the filter!"); + + + // + // Register data callbacks + // + + //Filter Data + DispatchHandler filter_data_handlers[5]; + + device->registerExtractor(filter_data_handlers[0], &filter_gps_time, 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]; + + device->registerExtractor(system_data_handlers[0], &system_time_sync_status, data_system::DESCRIPTOR_SET); + + // + //Resume the device + // + + if(commands_base::resume(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not resume the device!"); + + //Main Loop: Update the interface and process data + // + + bool running = true; + bool pps_sync_valid = false; + mip::Timestamp prev_print_timestamp = getCurrentTimestamp(); + mip::Timestamp prev_measurement_update_timestamp = getCurrentTimestamp(); + + printf("Sensor is configured... waiting for filter to initialize...\n"); + + while(running) { + mip::Timestamp current_timestamp = getCurrentTimestamp(); + + // Spin MIP device + device->update(); + + // Get ublox data + std::pair ubox_parser_result = ublox_device.update(); + bool pvt_message_valid = ubox_parser_result.first; + ublox::UbloxPVTMessage pvt_message = ubox_parser_result.second; + + // Wait for valid PPS lock + if (input_arguments.enable_pps_sync && !pps_sync_valid) + { + pps_sync_valid = system_time_sync_status.time_sync; + + mip::Timestamp elapsed_time_from_last_message_print = current_timestamp - prev_print_timestamp; + if (elapsed_time_from_last_message_print > 1000) + { + printf("Waiting for valid PPS lock...\n"); + prev_print_timestamp = current_timestamp; + } + continue; + } + + //Check for full nav filter state transition + if((!filter_state_full_nav) && (filter_status.filter_state == data_filter::FilterMode::FULL_NAV)) + { + printf("NOTE: Filter has entered full navigation mode.\n"); + filter_state_full_nav = true; + } + + //Print status at 1Hz + mip::Timestamp elapsed_time_from_last_message_print = current_timestamp - prev_print_timestamp; + 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) + { + printf("\n\n****Filter navigation state****\n"); + printf("TIMESTAMP: %f\n", filter_gps_time.tow); + printf("ATTITUDE_EULER = [%f %f %f]\n", filter_euler_angles.roll, filter_euler_angles.pitch, filter_euler_angles.yaw); + printf("LLH_POSITION = [%f %f %f]\n", filter_llh_position.latitude, filter_llh_position.longitude, filter_llh_position.ellipsoid_height); + printf("NED_VELOCITY = [%f %f %f]\n", filter_ned_velocity.north, filter_ned_velocity.east, filter_ned_velocity.down); + } + else + printf("Waiting for navigation filter to initialize...\n"); + + prev_print_timestamp = current_timestamp; + } + + // Check if measurement update is valid to send + mip::Timestamp elapsed_time_from_last_measurement_update = current_timestamp - prev_measurement_update_timestamp; + bool ublox_data_valid = pvt_message_valid && pvt_message.time_valid && pvt_message.llh_position_valid; + bool send_measurement_update = ublox_data_valid && elapsed_time_from_last_measurement_update > 250; // Cap maximum GNSS measurement input rate to 4hz + + if (send_measurement_update) + { + printf("\n\n****Sending Measurement Update****\n"); + 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; + 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)) + 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); + 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"); + + // Mark timestamp for aiding message input + external_measurement_time.timebase = 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.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) + 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) + printf("WARNING: Failed to send external NED velocity to CV7-INS\n"); + + prev_measurement_update_timestamp = current_timestamp; + } + + running = !should_exit(); + } + + exit_gracefully("Example Completed Successfully."); + +} + +//////////////////////////////////////////////////////////////////////////////// +// Utility functions +//////////////////////////////////////////////////////////////////////////////// + +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); +} + +time_t time_from_ymd(int year, int month, int day) +{ + struct tm tm = {0}; + tm.tm_year = year - 1900; + tm.tm_mon = month - 1; + tm.tm_mday = day; + return mktime(&tm); +} + +#define SECS_PER_WEEK (60L*60*24*7) + +int get_gps_week(int year, int month, int day) +{ + // See update below + double diff = difftime(time_from_ymd(year, month, day), time_from_ymd(1980, 1, 1)); // See update + return (int) (diff / SECS_PER_WEEK); +} + +//////////////////////////////////////////////////////////////////////////////// +// Print device information +//////////////////////////////////////////////////////////////////////////////// + +void print_device_information(const commands_base::BaseDeviceInfo& device_info) +{ + printf("Connected to:\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: ", device_info.model_name); + print_info("Model number: ", device_info.model_number); + print_info("Serial Number: ", device_info.serial_number); + print_info("Device Options: ", device_info.device_options); + print_info("Lot Number: ", device_info.lot_number); + + printf( " Firmware version: %d.%d.%d\n\n", + (device_info.firmware_version / 1000), + (device_info.firmware_version / 100) % 10, + (device_info.firmware_version / 1) % 100 + ); +} + +//////////////////////////////////////////////////////////////////////////////// +// Parse input arguments +//////////////////////////////////////////////////////////////////////////////// + +InputArguments parse_input_arguments(int argc, const char* argv[]) +{ + // TODO: Set max arg check for this. + if (argc < 8) + { + usage(argv[0]); + exit_gracefully(nullptr); + } + + InputArguments input_arguments; + + // MIP device port parameters + input_arguments.mip_device_port_name = argv[1]; + input_arguments.mip_device_baudrate = argv[2]; + + // UBlox device port parameters + input_arguments.ublox_device_port_name = argv[3]; + input_arguments.ublox_device_baudrate = argv[4]; + + // GNSS antenna lever arm + input_arguments.gnss_antenna_lever_arm[0] = std::stof(argv[5]); + input_arguments.gnss_antenna_lever_arm[1] = std::stof(argv[6]); + input_arguments.gnss_antenna_lever_arm[2] = std::stof(argv[7]); + + // Heading alignment method + if (argc >= 9) + { + int heading_alignment_int = std::stoi(argv[8]); + + if (heading_alignment_int == 0) + input_arguments.filter_heading_alignment_method = commands_filter::InitializationConfiguration::AlignmentSelector::KINEMATIC; + else if (heading_alignment_int == 1) + input_arguments.filter_heading_alignment_method = commands_filter::InitializationConfiguration::AlignmentSelector::MAGNETOMETER; + else + exit_gracefully("Heading alignment selector out of range"); + } + + // Output binary data filepath + if (argc >= 10) + input_arguments.mip_binary_filepath = argv[9]; + + // PPS sync enable + if (argc >= 11) + input_arguments.enable_pps_sync = std::stoi(argv[10]); + + // PPS input pin ID + if (argc >= 12) + input_arguments.pps_input_pin_id = std::stoi(argv[11]); + + return input_arguments; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Print Usage Function +//////////////////////////////////////////////////////////////////////////////// + +int usage(const char* argv0) +{ + printf("Usage: %s [OPTIONAL, (0=Kinematic, 1=Magnetometer)] [OPTIONAL] [OPTIONAL, (bool, (0|1)] [OPTIONAL, (int, 1-4)] \n", argv0); + return 1; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Exit Function +//////////////////////////////////////////////////////////////////////////////// + +void exit_gracefully(const char *message) +{ + if(message) + printf("%s\n", message); + +#ifdef _WIN32 + std::cout << "Press ENTER to exit..." << std::endl; + int dummy = getchar(); +#endif + + exit(0); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Check for Exit Condition +//////////////////////////////////////////////////////////////////////////////// + +bool should_exit() +{ + return false; +} + diff --git a/examples/CV7_INS/simple_ublox_parser.hpp b/examples/CV7_INS/simple_ublox_parser.hpp new file mode 100644 index 000000000..5c54b9b85 --- /dev/null +++ b/examples/CV7_INS/simple_ublox_parser.hpp @@ -0,0 +1,133 @@ +///////////////////////////////////////////////////////////////////////////// +// +// simple_ublox_parser.hpp +// +// Basic UBlox binary message parser +// +// This class intends to be a simple helper utility for an example to demonstrate CV7-INS functionality and is not intended +// to be reused for any other application +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + +#pragma once + +#include +#include +#include +#include +#include + +const int HEADER_SIZE = 6; +const int CHECKSUM_SIZE = 2; + +namespace mip +{ + namespace ublox + { + + bool verify_checksum(const std::vector& packet) + { + uint8_t ck_a, ck_b; + + ck_a = 0; + ck_b = 0; + + int num_bytes = packet.size(); + int num_bytes_without_checksum = num_bytes - 2; + + for (int i = 2; i < num_bytes_without_checksum; i++) { + ck_a += packet[i]; + ck_b += ck_a; + } + + if (ck_a == packet[num_bytes - 2] && ck_b == packet[num_bytes - 1]) + return true; + + return false; + } + + + class UbloxMessageParser + { + public: + + UbloxMessageParser(std::function)> packet_callback) : _packet_callback( + packet_callback) + {} + + void parse_bytes(uint8_t *buffer, size_t num_input_bytes) + { + // Copy into parser buffer + for (size_t i = 0; i < num_input_bytes; i++) { + _buffer.emplace_back(buffer[i]); + } + + // Wait for header bytes + while (_buffer.size() >= 2) { + if (header_found()) + break; + + _buffer.pop_front(); + } + + // Check if header is valid + if (!header_found()) + return; + + // Check if buffer has full message header + if (_buffer.size() < 6) + return; + + // Get message length + uint8_t payload_length_bytes[2] = {_buffer[4], _buffer[5]}; + uint16_t payload_length; + memcpy(&payload_length, payload_length_bytes, sizeof(uint16_t)); + + unsigned int total_message_length = HEADER_SIZE + payload_length + CHECKSUM_SIZE; + + // Check if buffer contains full packet size + if (_buffer.size() < total_message_length) + return; + + // Extract packet + std::vector packet(total_message_length); + for (unsigned int i = 0; i < total_message_length; i++) + packet[i] = _buffer[i]; + + // Validate checksum + if (verify_checksum(packet)) { + // Call packet callback + _packet_callback(packet); + + // Clear packet from buffer + for (unsigned int i = 0; i < total_message_length; i++) + _buffer.pop_front(); + } else + _buffer.pop_front(); + } + + bool header_found() + { + if (_buffer.size() < 2) + return false; + + return (_buffer[0] == 0xB5) && (_buffer[1] == 0x62); + } + + protected: + + std::function)> _packet_callback; + + std::deque _buffer; + }; + } +} diff --git a/examples/CV7_INS/ublox_device.hpp b/examples/CV7_INS/ublox_device.hpp new file mode 100644 index 000000000..6ba8f5d6c --- /dev/null +++ b/examples/CV7_INS/ublox_device.hpp @@ -0,0 +1,194 @@ +///////////////////////////////////////////////////////////////////////////// +// +// ublox_device.hpp +// +// Basic UBlox serial device interface to parse out the UBlox UBX-NAV-PVT message from a serial port +// +// This class intends to be a simple helper utility for an example to demonstrate CV7-INS functionality and is not intended +// to be reused for any other application +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + +#pragma once + +#include + +#include "simple_ublox_parser.hpp" + +#include "mip/platform/serial_connection.hpp" + +#define PVT_PAYLOAD_SIZE 92 + +namespace mip +{ + namespace ublox + { + +#pragma pack(1) + struct UbloxPVTMessageRaw + { + uint32_t iTOW; + uint16_t utc_year; + uint8_t utc_month; + uint8_t utc_day; + uint8_t utc_hour; + uint8_t utc_minute; + uint8_t utc_second; + uint8_t time_valid_flag; + uint32_t time_accuracy; + int32_t nano_second; + uint8_t fix_type; + uint8_t fix_valid_flags; + uint8_t confirmed_time_date_flags; + uint8_t number_of_satellites; + int32_t longitude; + int32_t latitude; + int32_t height_above_ellipsoid; + int32_t height_above_sea_level; + uint32_t horizontal_accuracy; + uint32_t vertical_accuracy; + int32_t north_velocity; + int32_t east_velocity; + int32_t down_velocity; + int32_t ground_speed; + int32_t heading_of_motion_2d; + uint32_t speed_accuracy; + uint32_t heading_accuracy; + uint16_t pDOP; + uint8_t llh_invalid_flag; + uint8_t reserved_bytes[5]; + int32_t heading_of_vehicle; + int16_t magnetic_declination; + uint16_t magnetic_declination_accuracy; + }; +#pragma pack() + + + struct UbloxPVTMessage + { + // Time + uint16_t utc_year = 0; + uint8_t utc_month = 0; + uint8_t utc_day = 0; + float time_of_week = 0; + bool time_valid = false; + + // LLH position + double latitude = 0; + double longitude = 0; + double height_above_ellipsoid = 0; + float llh_position_uncertainty[3] = {0, 0, 0}; + bool llh_position_valid = false; + + // NED velocity + float ned_velocity[3] = {0, 0, 0}; + float ned_velocity_uncertainty[3] = {0, 0, 0}; + }; + + + UbloxPVTMessage extract_pvt_message(const uint8_t payload[PVT_PAYLOAD_SIZE]) + { + // Unpack raw UBlox message data + UbloxPVTMessageRaw ublox_message_raw; + std::memcpy(&ublox_message_raw, payload, sizeof(ublox_message_raw)); + + // Build output message with properly scaled units + UbloxPVTMessage ublox_message; + + // Time + 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_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_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; + for (int i = 0; i < 3; i++) + ublox_message.ned_velocity_uncertainty[i] = ublox_message_raw.speed_accuracy * 1e-3; + + return ublox_message; + } + + + class UbloxDevice + { + public: + + 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) + { + bool is_pvt_message = (packet[2] == 0x01) && (packet[3] == 0x07); + if (!is_pvt_message) + return; + + // Should never happen + size_t expected_packet_size = HEADER_SIZE + PVT_PAYLOAD_SIZE + CHECKSUM_SIZE; + if (packet.size() != expected_packet_size) + return; + + // Extract message payload + uint8_t payload_bytes[PVT_PAYLOAD_SIZE]; + for (int i = 0; i < PVT_PAYLOAD_SIZE; i++) + payload_bytes[i] = packet[i + HEADER_SIZE]; + + // Parse message payload + _current_message = extract_pvt_message(payload_bytes); + + // Mark flag indicating a new message has been received + _new_pvt_message_received = true; + } + + std::pair update() + { + // Reset new message indicator flag + _new_pvt_message_received = false; + + // Get incoming bytes from serial port + uint8_t input_bytes[1024]; + size_t num_input_bytes; + mip::Timestamp timestamp_out; + _connection->recvFromDevice(input_bytes, 1024, 1, &num_input_bytes, ×tamp_out); + + // Spin message parser + _message_parser.parse_bytes(input_bytes, num_input_bytes); + + return {_new_pvt_message_received, _current_message}; + } + + protected: + + std::unique_ptr _connection; + UbloxMessageParser _message_parser; + + bool _new_pvt_message_received = false; + UbloxPVTMessage _current_message; + }; + } +} \ No newline at end of file diff --git a/examples/GX5_45/GX5_45_example.c b/examples/CX5_GX5_45/CX5_GX5_45_example.c similarity index 92% rename from examples/GX5_45/GX5_45_example.c rename to examples/CX5_GX5_45/CX5_GX5_45_example.c index c10fd20f2..f1c8af86d 100644 --- a/examples/GX5_45/GX5_45_example.c +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.c @@ -1,9 +1,9 @@ ///////////////////////////////////////////////////////////////////////////// // -// GX5_45_Example.c +// CX5_GX5_45_Example.c // -// C Example set-up program for the GX5-45 +// C Example set-up program for the CX5-45 and GX5-45 // // This example shows a typical setup for the GX5-45 sensor in a wheeled-vehicle application using using C. // It is not an exhaustive example of all GX5-45 settings. @@ -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, PARKER MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN 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. @@ -29,11 +29,13 @@ #include #include + #include #include #include #include +//#include "example_utils.h" //////////////////////////////////////////////////////////////////////////////// // Global Variables @@ -77,9 +79,9 @@ bool filter_state_running = false; //Required MIP interface user-defined functions -timestamp_type get_current_timestamp(); +mip_timestamp get_current_timestamp(); -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, size_t* out_length, timestamp_type* 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); bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length); int usage(const char* argv0); @@ -129,7 +131,11 @@ int main(int argc, const char* argv[]) //Initialize the MIP interface // - mip_interface_init(&device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000); + mip_interface_init( + &device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000, + &mip_interface_user_send_to_device, &mip_interface_user_recv_from_device, &mip_interface_default_update, NULL + ); + // @@ -297,8 +303,8 @@ int main(int argc, const char* argv[]) //Main Loop: Update the interface and process data // - bool running = true; - timestamp_type prev_print_timestamp = 0; + bool running = true; + mip_timestamp prev_print_timestamp = 0; printf("Sensor is configured... waiting for filter to enter running mode.\n"); @@ -325,7 +331,7 @@ int main(int argc, const char* argv[]) //Once in running mode, print out data at 1 Hz if(filter_state_running) { - timestamp_type curr_time = get_current_timestamp(); + mip_timestamp curr_time = get_current_timestamp(); if(curr_time - prev_print_timestamp >= 1000) { @@ -349,12 +355,12 @@ int main(int argc, const char* argv[]) // MIP Interface Time Access Function //////////////////////////////////////////////////////////////////////////////// -timestamp_type get_current_timestamp() +mip_timestamp get_current_timestamp() { clock_t curr_time; curr_time = clock(); - return (timestamp_type)((double)(curr_time - start_time)/(double)CLOCKS_PER_SEC*1000.0); + return (mip_timestamp)((double)(curr_time - start_time) / (double)CLOCKS_PER_SEC * 1000.0); } @@ -362,10 +368,10 @@ timestamp_type 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, size_t* out_length, timestamp_type* 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) { *timestamp_out = get_current_timestamp(); - return serial_port_read(&device_port, buffer, max_length, out_length); + return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); } diff --git a/examples/GX5_45/GX5_45_example.cpp b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp similarity index 94% rename from examples/GX5_45/GX5_45_example.cpp rename to examples/CX5_GX5_45/CX5_GX5_45_example.cpp index 2305f2e69..484444522 100644 --- a/examples/GX5_45/GX5_45_example.cpp +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp @@ -1,9 +1,9 @@ ///////////////////////////////////////////////////////////////////////////// // -// GX5_45_Example.cpp +// CX5_GX5_45_Example.cpp // -// C++ Example set-up program for the GX5-45 +// C++ Example set-up program for the CX5-45 and GX5-45 // // This example shows a typical setup for the GX5-45 sensor in a wheeled-vehicle application using using C++. // It is not an exhaustive example of all GX5-45 settings. @@ -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, PARKER MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN 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. @@ -28,8 +28,10 @@ //////////////////////////////////////////////////////////////////////////////// #include + #include -#include "../example_utils.hpp" + +#include "example_utils.hpp" using namespace mip; @@ -82,9 +84,17 @@ bool should_exit(); int main(int argc, const char* argv[]) { - std::unique_ptr utils = handleCommonArgs(argc, argv); - std::unique_ptr& device = utils->device; + 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; printf("Connecting to and configuring sensor.\n"); // @@ -256,11 +266,13 @@ int main(int argc, const char* argv[]) bool running = true; mip::Timestamp prev_print_timestamp = getCurrentTimestamp(); - printf("Sensor is configured... waiting for filter to enter running mode.\n"); + printf("Sensor is configured... waiting for filter to enter running mode (GX5_RUN_SOLUTION_VALID).\n"); + std::string current_state = std::string{""}; while(running) { device->update(); + 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) && @@ -321,6 +333,7 @@ void exit_gracefully(const char *message) printf("%s\n", message); #ifdef _WIN32 + 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 new file mode 100644 index 000000000..4721360cc --- /dev/null +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c @@ -0,0 +1,380 @@ + +///////////////////////////////////////////////////////////////////////////// +// +// CX5_GX5_CV5_15_25_Example.c +// +// C Example set-up program for the CX5-15, CX5-25, GX5-15, GX5-25, CV5-15, and CV5-25. +// +// This example shows a typical setup for the CX5-15 sensor in a wheeled-vehicle application using using C. +// It is not an exhaustive example of all CX5-15 settings. +// If your specific setup needs are not met by this example, please consult +// the MSCL-embedded API documentation for the proper commands. +// +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + + +//////////////////////////////////////////////////////////////////////////////// +// Include Files +//////////////////////////////////////////////////////////////////////////////// + +#include +#include + +#include +#include +#include +#include + +//#include "example_utils.h" + +//////////////////////////////////////////////////////////////////////////////// +// Global Variables +//////////////////////////////////////////////////////////////////////////////// + +serial_port device_port; +clock_t start_time; + +int port = -1; +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}; + +//Device data stores +mip_sensor_gps_timestamp_data sensor_gps_time; +mip_sensor_scaled_accel_data sensor_accel; +mip_sensor_scaled_gyro_data sensor_gyro; + +mip_filter_timestamp_data filter_gps_time; +mip_filter_status_data filter_status; +mip_filter_euler_angles_data filter_euler_angles; +mip_filter_comp_angular_rate_data filter_comp_angular_rate; +mip_filter_comp_accel_data filter_comp_accel; + +bool filter_state_running = false; + + +//////////////////////////////////////////////////////////////////////////////// +// Function Prototypes +//////////////////////////////////////////////////////////////////////////////// + + +//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); + +int usage(const char* argv0); + +void exit_gracefully(const char *message); +bool should_exit(); + + +//////////////////////////////////////////////////////////////////////////////// +// Main Function +//////////////////////////////////////////////////////////////////////////////// + + +int main(int argc, const char* argv[]) +{ + + // + //Process arguments + // + + if(argc != 3) + return usage(argv[0]); + + const char* port_name = argv[1]; + uint32_t baudrate = atoi(argv[2]); + + if(baudrate == 0) + return usage(argv[0]); + + // + //Get the program start time + // + + start_time = clock(); + + printf("Connecting to and configuring sensor.\n"); + + // + //Open the device port + // + + if(!serial_port_open(&device_port, port_name, baudrate)) + exit_gracefully("ERROR: Could not open device port!"); + + + // + //Initialize the MIP interface + // + + mip_interface_init( + &device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000, + &mip_interface_user_send_to_device, &mip_interface_user_recv_from_device, &mip_interface_default_update, NULL + ); + + + + // + //Ping the device (note: this is good to do to make sure the device is present) + // + + if(mip_base_ping(&device) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not ping the device!"); + + + // + //Idle the device (note: this is good to do during setup) + // + + if(mip_base_set_idle(&device) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not set the device to idle!"); + + + // + //Load the device default settings (so the device is in a known state) + // + + if(mip_3dm_default_device_settings(&device) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not load default device settings!"); + + 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); + 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}; + + if(mip_3dm_capture_gyro_bias(&device, sampling_time, gyro_bias) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not load default device settings!"); + + mip_cmd_queue_set_base_reply_timeout(queue, old_mip_sdk_timeout); + + // + //Setup Sensor data format to 100 Hz + // + + uint16_t sensor_base_rate; + + //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(mip_3dm_imu_get_base_rate(&device, &sensor_base_rate) != MIP_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; + + const mip_descriptor_rate sensor_descriptors[3] = { + { MIP_DATA_DESC_SENSOR_TIME_STAMP_GPS, sensor_decimation }, + { MIP_DATA_DESC_SENSOR_ACCEL_SCALED, sensor_decimation }, + { MIP_DATA_DESC_SENSOR_GYRO_SCALED, sensor_decimation }, + }; + + if(mip_3dm_write_imu_message_format(&device, 3, sensor_descriptors) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not set sensor message format!"); + + + // + //Setup FILTER data format + // + + uint16_t filter_base_rate; + + if(mip_3dm_filter_get_base_rate(&device, &filter_base_rate) != MIP_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; + + const mip_descriptor_rate filter_descriptors[5] = { + { MIP_DATA_DESC_FILTER_FILTER_TIMESTAMP, filter_decimation }, + { MIP_DATA_DESC_FILTER_FILTER_STATUS, filter_decimation }, + { MIP_DATA_DESC_FILTER_ATT_EULER_ANGLES, filter_decimation }, + { MIP_DATA_DESC_FILTER_COMPENSATED_ANGULAR_RATE, filter_decimation }, + { MIP_DATA_DESC_FILTER_COMPENSATED_ACCELERATION, filter_decimation }, + }; + + if(mip_3dm_write_filter_message_format(&device, 5, filter_descriptors) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not set filter message format!"); + + + // + //Setup the sensor to vehicle rotation + // + + if(mip_filter_write_sensor_to_vehicle_rotation_euler(&device, sensor_to_vehicle_rotation_euler[0], sensor_to_vehicle_rotation_euler[1], sensor_to_vehicle_rotation_euler[2]) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not set sensor-2-vehicle rotation!"); + + // + //Enable filter auto-initialization + // + + if(mip_filter_write_auto_init_control(&device, 1) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not set filter autoinit control!"); + + // + // Register data callbacks + // + + //Sensor Data + mip_dispatch_handler sensor_data_handlers[3]; + + mip_interface_register_extractor(&device, &sensor_data_handlers[0], MIP_SENSOR_DATA_DESC_SET, MIP_DATA_DESC_SENSOR_TIME_STAMP_GPS, extract_mip_sensor_gps_timestamp_data_from_field, &sensor_gps_time); + mip_interface_register_extractor(&device, &sensor_data_handlers[1], MIP_SENSOR_DATA_DESC_SET, MIP_DATA_DESC_SENSOR_ACCEL_SCALED, extract_mip_sensor_scaled_accel_data_from_field, &sensor_accel); + mip_interface_register_extractor(&device, &sensor_data_handlers[2], MIP_SENSOR_DATA_DESC_SET, MIP_DATA_DESC_SENSOR_GYRO_SCALED, extract_mip_sensor_scaled_gyro_data_from_field, &sensor_gyro); + + //Filter Data + mip_dispatch_handler filter_data_handlers[5]; + + mip_interface_register_extractor(&device, &filter_data_handlers[0], MIP_FILTER_DATA_DESC_SET, MIP_DATA_DESC_FILTER_FILTER_TIMESTAMP, extract_mip_filter_timestamp_data_from_field, &filter_gps_time); + mip_interface_register_extractor(&device, &filter_data_handlers[1], MIP_FILTER_DATA_DESC_SET, MIP_DATA_DESC_FILTER_FILTER_STATUS, extract_mip_filter_status_data_from_field, &filter_status); + mip_interface_register_extractor(&device, &filter_data_handlers[2], MIP_FILTER_DATA_DESC_SET, MIP_DATA_DESC_FILTER_ATT_EULER_ANGLES, extract_mip_filter_euler_angles_data_from_field, &filter_euler_angles); + mip_interface_register_extractor(&device, &filter_data_handlers[3], MIP_FILTER_DATA_DESC_SET, MIP_DATA_DESC_FILTER_COMPENSATED_ANGULAR_RATE, extract_mip_filter_comp_angular_rate_data_from_field, &filter_comp_angular_rate); + mip_interface_register_extractor(&device, &filter_data_handlers[4], MIP_FILTER_DATA_DESC_SET, MIP_DATA_DESC_FILTER_COMPENSATED_ACCELERATION, extract_mip_filter_comp_accel_data_from_field, &filter_comp_accel); + + + // + //Resume the device + // + + if(mip_base_resume(&device) != MIP_ACK_OK) + exit_gracefully("ERROR: Could not resume the device!"); + + + // + //Main Loop: Update the interface and process data + // + + bool running = true; + mip_timestamp prev_print_timestamp = 0; + + printf("Sensor is configured... waiting for filter to enter running mode.\n"); + + while(running) + { + mip_interface_update(&device, false); + + //Check Filter State + if((!filter_state_running) && ((filter_status.filter_state == MIP_FILTER_MODE_GX5_RUN_SOLUTION_ERROR) || (filter_status.filter_state == MIP_FILTER_MODE_GX5_RUN_SOLUTION_VALID))) + { + printf("NOTE: Filter has entered running mode.\n"); + filter_state_running = true; + } + + //Once in running mode, print out data at 1 Hz + if(filter_state_running) + { + mip_timestamp curr_time = get_current_timestamp(); + + if(curr_time - 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_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]); + + prev_print_timestamp = curr_time; + } + } + + running = !should_exit(); + } + + exit_gracefully("Example Completed Successfully."); +} + + +//////////////////////////////////////////////////////////////////////////////// +// MIP Interface Time Access Function +//////////////////////////////////////////////////////////////////////////////// + +mip_timestamp get_current_timestamp() +{ + clock_t curr_time; + curr_time = clock(); + + return (mip_timestamp)((double)(curr_time - start_time)/(double)CLOCKS_PER_SEC*1000.0); +} + + +//////////////////////////////////////////////////////////////////////////////// +// 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) +{ + *timestamp_out = get_current_timestamp(); + return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); +} + + +//////////////////////////////////////////////////////////////////////////////// +// MIP Interface User Send Data Function +//////////////////////////////////////////////////////////////////////////////// + +bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length) +{ + size_t bytes_written; + + return serial_port_write(&device_port, data, length, &bytes_written); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Print Usage Function +//////////////////////////////////////////////////////////////////////////////// + +int usage(const char* argv0) +{ + printf("Usage: %s \n", argv0); + return 1; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Exit Function +//////////////////////////////////////////////////////////////////////////////// + +void exit_gracefully(const char *message) +{ + if(message) + printf("%s\n", message); + + //Close com port + if(serial_port_is_open(&device_port)) + serial_port_close(&device_port); + +#ifdef _WIN32 + int dummy = getchar(); +#endif + + exit(0); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Check for Exit Condition +//////////////////////////////////////////////////////////////////////////////// + +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 new file mode 100644 index 000000000..74bd0b228 --- /dev/null +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp @@ -0,0 +1,313 @@ + +///////////////////////////////////////////////////////////////////////////// +// +// CX5_GX5_CV5_15_25_Example.cpp +// +// C++ Example set-up program for the CX5-15, CX5-25, GX5-15, GX5-25, CV5-15, and CV5-25. +// +// This example shows a typical setup for the CX5-15 sensor in a wheeled-vehicle application using using C++. +// It is not an exhaustive example of all CX5-15 settings. +// If your specific setup needs are not met by this example, please consult +// the MSCL-embedded API documentation for the proper commands. +// +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + + +//////////////////////////////////////////////////////////////////////////////// +// Include Files +//////////////////////////////////////////////////////////////////////////////// + +#include +#include +#include "../example_utils.hpp" + +using namespace mip; + + +//////////////////////////////////////////////////////////////////////////////// +// Global Variables +//////////////////////////////////////////////////////////////////////////////// + + +//Sensor-to-vehicle frame rotation (Euler Angles) +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; + +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; + +bool filter_state_running = false; + + +//////////////////////////////////////////////////////////////////////////////// +// Function Prototypes +//////////////////////////////////////////////////////////////////////////////// + +int usage(const char* argv0); + +void exit_gracefully(const char *message); +bool should_exit(); + + +//////////////////////////////////////////////////////////////////////////////// +// Main Function +//////////////////////////////////////////////////////////////////////////////// + + +int main(int argc, const char* argv[]) +{ + + std::unique_ptr utils = handleCommonArgs(argc, argv); + std::unique_ptr& device = utils->device; + + printf("Connecting to and configuring sensor.\n"); + + // + //Ping the device (note: this is good to do to make sure the device is present) + // + + if(commands_base::ping(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not ping the device!"); + + + // + //Idle the device (note: this is good to do during setup) + // + + if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not set the device to idle!"); + + + // + //Load the device default settings (so the device is in a known state) + // + + if(commands_3dm::defaultDeviceSettings(*device) != 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 int32_t 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) + exit_gracefully("ERROR: Could not capture gyro bias!"); + + 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) + exit_gracefully("ERROR: Could not enable device data stream!"); + + // Reset the timeout + device->setBaseReplyTimeout(old_mip_sdk_timeout); + + printf("Gyro bias captured with sampling time: %d, and gyro bias captured as: %f %f %f.\n", sampling_time, gyro_bias[0], gyro_bias[1], gyro_bias[2]); + + + // + //Setup Sensor data format to 100 Hz + // + + uint16_t sensor_base_rate; + + //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) + 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 }, + }}; + + if(commands_3dm::writeImuMessageFormat(*device, sensor_descriptors.size(), sensor_descriptors.data()) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not set sensor message format!"); + + + // + //Setup FILTER data format + // + + uint16_t filter_base_rate; + + if(commands_3dm::filterGetBaseRate(*device, &filter_base_rate) != 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 }, + }}; + + if(commands_3dm::writeFilterMessageFormat(*device, filter_descriptors.size(), filter_descriptors.data()) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not set filter message format!"); + + + // + //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) + exit_gracefully("ERROR: Could not set sensor-2-vehicle rotation!"); + + // + //Enable filter auto-initialization + // + + if(commands_filter::writeAutoInitControl(*device, 1) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not set filter autoinit control!"); + + + + // + //Reset the filter (note: this is good to do after filter setup is complete) + // + + if(commands_filter::reset(*device) != CmdResult::ACK_OK) + exit_gracefully("ERROR: Could not reset the filter!"); + + + // + // Register data callbacks + // + + //Sensor Data + 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]; + + 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) + exit_gracefully("ERROR: Could not resume the device!"); + + + // + //Main Loop: Update the interface and process data + // + + bool running = true; + mip::Timestamp prev_print_timestamp = getCurrentTimestamp(); + + printf("Sensor is configured... waiting for filter to enter running mode.\n"); + + 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))) + { + printf("NOTE: Filter has entered running mode.\n"); + filter_state_running = true; + } + + //Once in running mode, print out data at 1 Hz + if(filter_state_running) + { + mip::Timestamp curr_timestamp = getCurrentTimestamp(); + + 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_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]); + + prev_print_timestamp = curr_timestamp; + } + } + + running = !should_exit(); + } + + exit_gracefully("Example Completed Successfully."); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Print Usage Function +//////////////////////////////////////////////////////////////////////////////// + +int usage(const char* argv0) +{ + printf("Usage: %s \n", argv0); + return 1; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Exit Function +//////////////////////////////////////////////////////////////////////////////// + +void exit_gracefully(const char *message) +{ + if(message) + printf("%s\n", message); + +#ifdef _WIN32 + int dummy = getchar(); +#endif + + exit(0); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Check for Exit Condition +//////////////////////////////////////////////////////////////////////////////// + +bool should_exit() +{ + return false; + +} + diff --git a/examples/GQ7/GQ7_example.c b/examples/GQ7/GQ7_example.c index 9d0f8e01f..4e575d702 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, PARKER MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN 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. @@ -34,6 +34,8 @@ #include #include +#include "example_utils.h" + //////////////////////////////////////////////////////////////////////////////// // Global Variables @@ -78,9 +80,9 @@ bool filter_state_full_nav = false; //Required MIP interface user-defined functions -timestamp_type get_current_timestamp(); +mip_timestamp get_current_timestamp(); -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, size_t* out_length, timestamp_type* 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); bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length); int usage(const char* argv0); @@ -130,7 +132,11 @@ int main(int argc, const char* argv[]) //Initialize the MIP interface // - mip_interface_init(&device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000); + mip_interface_init( + &device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000, + &mip_interface_user_send_to_device, &mip_interface_user_recv_from_device, &mip_interface_default_update, NULL + ); + // @@ -323,15 +329,17 @@ int main(int argc, const char* argv[]) //Main Loop: Update the interface and process data // - bool running = true; - timestamp_type prev_print_timestamp = 0; + bool running = true; + mip_timestamp prev_print_timestamp = 0; printf("Sensor is configured... waiting for filter to enter Full Navigation mode.\n"); + char *state_init = ""; + char **current_state = &state_init; while(running) { mip_interface_update(&device, false); - + displayFilterState(filter_status.filter_state, current_state, false); //Check GNSS fixes and alert the user when they become valid for(int i=0; i<2; i++) @@ -356,7 +364,7 @@ int main(int argc, const char* argv[]) //Once in full nav, print out data at 1 Hz if(filter_state_full_nav) { - timestamp_type curr_time = get_current_timestamp(); + mip_timestamp curr_time = get_current_timestamp(); if(curr_time - prev_print_timestamp >= 1000) { @@ -380,12 +388,12 @@ int main(int argc, const char* argv[]) // MIP Interface Time Access Function //////////////////////////////////////////////////////////////////////////////// -timestamp_type get_current_timestamp() +mip_timestamp get_current_timestamp() { clock_t curr_time; curr_time = clock(); - return (timestamp_type)((double)(curr_time - start_time)/(double)CLOCKS_PER_SEC*1000.0); + return (mip_timestamp)((double)(curr_time - start_time) / (double)CLOCKS_PER_SEC * 1000.0); } @@ -393,10 +401,10 @@ timestamp_type 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, size_t* out_length, timestamp_type* 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) { *timestamp_out = get_current_timestamp(); - return serial_port_read(&device_port, buffer, max_length, out_length); + return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); } @@ -453,4 +461,3 @@ bool should_exit() return false; } - diff --git a/examples/GQ7/GQ7_example.cpp b/examples/GQ7/GQ7_example.cpp index e1390b016..0b2f1ba8b 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, PARKER MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN 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. @@ -28,8 +28,10 @@ //////////////////////////////////////////////////////////////////////////////// #include + #include -#include "../example_utils.hpp" + +#include "example_utils.hpp" using namespace mip; @@ -82,9 +84,17 @@ bool should_exit(); int main(int argc, const char* argv[]) { - std::unique_ptr utils = handleCommonArgs(argc, argv); - std::unique_ptr& device = utils->device; + 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; printf("Connecting to and configuring sensor.\n"); // @@ -286,12 +296,12 @@ int main(int argc, const char* argv[]) bool running = true; mip::Timestamp prev_print_timestamp = getCurrentTimestamp(); - printf("Sensor is configured... waiting for filter to enter Full Navigation mode.\n"); + printf("Sensor is configured... waiting for filter to enter Full Navigation mode (FULL_NAV).\n"); - while(running) - { + std::string current_state = std::string{""}; + while(running) { device->update(); - + displayFilterState(filter_status.filter_state, current_state); //Check GNSS fixes and alert the user when they become valid for(int i=0; i<2; i++) @@ -357,6 +367,7 @@ void exit_gracefully(const char *message) printf("%s\n", message); #ifdef _WIN32 + printf("Press ENTER to exit...\n"); int dummy = getchar(); #endif diff --git a/examples/device_info.cpp b/examples/device_info.cpp index 740d5656c..7c9c454a7 100644 --- a/examples/device_info.cpp +++ b/examples/device_info.cpp @@ -1,8 +1,24 @@ +///////////////////////////////////////////////////////////////////////////// +// +// device_info.cpp +// +// C++ example program to print device information from any mip-enabled MicroStrain device. +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + #include "example_utils.hpp" #include -#include #include #include diff --git a/examples/example_utils.c b/examples/example_utils.c new file mode 100644 index 000000000..8713585f7 --- /dev/null +++ b/examples/example_utils.c @@ -0,0 +1,25 @@ +#include "example_utils.h" + +#include +#include + +void displayFilterState(const mip_filter_mode filter_state, char **current_state, bool isFiveSeries) +{ + char *read_state = ""; + if (filter_state == MIP_FILTER_MODE_INIT) + read_state = isFiveSeries ? "GX5_INIT (1)" : "INIT (1)"; + else if (filter_state == MIP_FILTER_MODE_VERT_GYRO) + read_state = isFiveSeries ? "GX5_RUN_SOLUTION_VALID (2)" : "VERT_GYRO (2)"; + else if (filter_state == MIP_FILTER_MODE_AHRS) + read_state = isFiveSeries ? "GX5_RUN_SOLUTION_ERROR (3)" : "AHRS (3)"; + else if (filter_state == MIP_FILTER_MODE_FULL_NAV) + read_state = "FULL_NAV (4)"; + else + read_state = "STARTUP (0)"; + + if (strcmp(read_state, *current_state) != 0) + { + printf("FILTER STATE: %s\n", read_state); + *current_state = read_state; + } +} \ No newline at end of file diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index 8009adfc4..0e47a84fe 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -1,6 +1,10 @@ #include #include +#include + +#include + #include "example_utils.hpp" @@ -16,10 +20,48 @@ 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) +{ + // Convert the varargs into a string + std::string log; + va_list args_copy; + va_copy(args_copy, args); + const int required_len = vsnprintf(nullptr, 0, fmt, args_copy); + if (required_len >= 0) + { + log.resize(required_len); + vsnprintf(&log[0], required_len + 1, fmt, args); + } + va_end(args_copy); -std::unique_ptr openFromArgs(const std::string& port_or_hostname, const std::string& baud_or_port) + // Print to the proper stream + switch (level) + { + case MIP_LOG_LEVEL_FATAL: + case MIP_LOG_LEVEL_ERROR: + std::cerr << log; + break; + default: + std::cout << log; + break; + } +} + +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()); + + if( !binary_file_path.empty() ) + { +#ifdef MIP_USE_EXTRAS + example_utils->recordedFile = std::unique_ptr(new std::ofstream(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 + } + if(port_or_hostname.find(PORT_KEY) == std::string::npos) // Not a serial port { @@ -28,7 +70,14 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, if( port < 1024 || port > 65535 ) throw std::runtime_error("Invalid TCP port (must be between 1024 and 65535."); - example_utils->connection = std::unique_ptr(new mip::platform::TcpConnection(port_or_hostname, port)); +#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)); +#else // MIP_USE_EXTRAS + using TcpConnection = mip::platform::TcpConnection; + example_utils->connection = std::unique_ptr(new TcpConnection(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)); #else // MIP_USE_TCP throw std::runtime_error("This program was compiled without socket support. Recompile with -DMIP_USE_TCP=1"); @@ -43,28 +92,74 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, if( baud == 0 ) throw std::runtime_error("Serial baud rate must be a decimal integer greater than 0."); - example_utils->connection = std::unique_ptr(new mip::platform::SerialConnection(port_or_hostname, baud)); +#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)); +#else // MIP_USE_EXTRAS + using SerialConnection = mip::platform::SerialConnection; + example_utils->connection = std::unique_ptr(new SerialConnection(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)); #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 } + + if( !example_utils->connection->connect() ) + throw std::runtime_error("Failed to open the connection"); + return example_utils; } 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); + if( argc < 3 || argc > maxArgs ) { throw std::underflow_error("Usage error"); } - return openFromArgs(argv[1], argv[2]); + // If we were passed a file name, record the data in that file + std::string binary_file_path = ""; + if (argc >= 4) + binary_file_path = argv[3]; + + return openFromArgs(argv[1], argv[2], binary_file_path); } int printCommonUsage(const char* argv[]) { - fprintf(stderr, "Usage: %s \nUsage: %s \n", argv[0], argv[0]); + fprintf(stderr, "Usage: %s \nUsage: %s \n", argv[0], argv[0]); return 1; } +void displayFilterState(const mip::data_filter::FilterMode &filterState, std::string ¤tState, bool isFiveSeries) { + std::string read_state = ""; + switch (filterState) + { + case mip::data_filter::FilterMode::INIT: + read_state = (isFiveSeries ? "GX5_INIT" : "INIT") + std::string(" (1)"); + break; + case mip::data_filter::FilterMode::VERT_GYRO: + read_state = (isFiveSeries ? "GX5_RUN_SOLUTION_VALID" : "VERT_GYRO") + std::string(" (2)"); + break; + case mip::data_filter::FilterMode::AHRS: + read_state = (isFiveSeries ? "GX5_RUN_SOLUTION_ERROR" : "AHRS") + std::string(" (3)"); + break; + case mip::data_filter::FilterMode::FULL_NAV: + read_state = "FULL_NAV (4)"; + break; + default: + read_state = "STARTUP (0)"; + break; + } + + if (read_state != currentState) + { + printf("Filter state: %s\n", read_state.data()); + currentState = read_state; + } +} diff --git a/examples/example_utils.h b/examples/example_utils.h new file mode 100644 index 000000000..34668af1e --- /dev/null +++ b/examples/example_utils.h @@ -0,0 +1,5 @@ +#include + + +// Displays current filter state for the connected device if it has changed. +void displayFilterState(const mip_filter_mode filterState, char **currentState, bool isFiveSeries); diff --git a/examples/example_utils.hpp b/examples/example_utils.hpp index fe29d4dcf..7ede3b40c 100644 --- a/examples/example_utils.hpp +++ b/examples/example_utils.hpp @@ -7,23 +7,34 @@ #ifdef MIP_USE_TCP #include "mip/platform/tcp_connection.hpp" #endif +#ifdef MIP_USE_EXTRAS + #include "mip/extras/recording_connection.hpp" +#endif + #include +#include #include #include +#include +#include #include struct ExampleUtils { std::unique_ptr connection; std::unique_ptr device; + std::unique_ptr recordedFile; uint8_t buffer[1024]; }; mip::Timestamp getCurrentTimestamp(); -std::unique_ptr openFromArgs(const std::string& port_or_hostname, const std::string& baud_or_port); +std::unique_ptr openFromArgs(const std::string& port_or_hostname, const std::string& baud_or_port, const std::string& binary_file_path); -std::unique_ptr handleCommonArgs(int argc, const char* argv[], int maxArgs=3); +std::unique_ptr handleCommonArgs(int argc, const char* argv[], int maxArgs=4); int printCommonUsage(const char* argv[]); + +/// Displays current filter state for the connected device if it has changed. +void displayFilterState(const mip::data_filter::FilterMode &filterState, std::string ¤tState, bool isFiveSeries = false); 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/examples/threading.cpp b/examples/threading.cpp index dd58dc340..c12cdf5c4 100644 --- a/examples/threading.cpp +++ b/examples/threading.cpp @@ -1,4 +1,21 @@ +///////////////////////////////////////////////////////////////////////////// +// +// threading.cpp +// +// C++ example program to print device information from any mip-enabled MicroStrain device. +// +//!@section LICENSE +//! +//! 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 +//! 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. +// +///////////////////////////////////////////////////////////////////////////// + #include "example_utils.hpp" #include @@ -41,7 +58,7 @@ unsigned int display_progress() return count; } -void packet_callback(void*, const mip::Packet& packet, mip::Timestamp timestamp) +void packet_callback(void*, const mip::PacketRef& packet, mip::Timestamp timestamp) { numSamples++; } @@ -50,7 +67,7 @@ void device_thread_loop(mip::DeviceInterface* device) { while(!stop) { - if( !device->update(false) ) + if( !device->update(0) ) { device->cmdQueue().clear(); // Avoid deadlocks if the socket is closed. break; @@ -60,15 +77,18 @@ void device_thread_loop(mip::DeviceInterface* device) } } -bool update_device(mip::DeviceInterface& device, bool blocking) +bool update_device(mip::DeviceInterface& device, mip::Timeout wait_time) { - if( !blocking ) - return device.defaultUpdate(blocking); + // Thread calls this with wait_time 0, commands have wait_time > 0. + if( wait_time == 0 ) + return device.defaultUpdate(wait_time); // Optionally display progress while waiting for command replies. // Displaying it here makes it update more frequently. //display_progress(); + // Avoid failing the update function as long as the other thread is running. + // Doing so may cause a race condition (see comments in mip_interface_wait_for_reply). std::this_thread::sleep_for(std::chrono::milliseconds(5)); return true; } diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 937b6a53b..7fd76467d 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -4,6 +4,7 @@ #include #include #include +#include #include #include @@ -13,10 +14,14 @@ #include +#include + #include #include #include #include +#include +#include #ifdef WIN32 #else @@ -31,7 +36,21 @@ uint8_t parse_buffer[1024]; mip_interface device; mip_sensor_scaled_accel_data scaled_accel; -void handlePacket(void* unused, const mip_packet* packet, timestamp_type timestamp) +void customLog(void* user, mip_log_level level, const char* fmt, va_list args) +{ + switch (level) + { + case MIP_LOG_LEVEL_FATAL: + case MIP_LOG_LEVEL_ERROR: + vfprintf(stderr, fmt, args); + break; + default: + vprintf(fmt, args); + break; + } +} + +void handlePacket(void* unused, const mip_packet* packet, mip_timestamp timestamp) { (void)unused; @@ -46,7 +65,7 @@ void handlePacket(void* unused, const mip_packet* packet, timestamp_type timesta printf("\n"); } -void handleAccel(void* user, const mip_field* field, timestamp_type timestamp) +void handleAccel(void* user, const mip_field* field, mip_timestamp timestamp) { (void)user; mip_sensor_scaled_accel_data data; @@ -63,7 +82,7 @@ void handleAccel(void* user, const mip_field* field, timestamp_type timestamp) } } -void handleGyro(void* user, const mip_field* field, timestamp_type timestamp) +void handleGyro(void* user, const mip_field* field, mip_timestamp timestamp) { (void)user; mip_sensor_scaled_gyro_data data; @@ -72,7 +91,7 @@ void handleGyro(void* user, const mip_field* field, timestamp_type 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, timestamp_type timestamp) +void handleMag(void* user, const mip_field* field, mip_timestamp timestamp) { (void)user; mip_sensor_scaled_mag_data data; @@ -84,23 +103,23 @@ void handleMag(void* user, const mip_field* field, timestamp_type timestamp) time_t startTime; -timestamp_type get_current_timestamp() +mip_timestamp get_current_timestamp() { time_t t; time(&t); double delta = difftime(t, startTime); - return (timestamp_type)(delta * 1000); + return (mip_timestamp)(delta * 1000); } -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, size_t* out_length, timestamp_type* 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(); - if( !serial_port_read(&port, buffer, max_length, out_length) ) + if( !serial_port_read(&port, buffer, max_length, wait_time, out_length) ) return false; return true; @@ -139,10 +158,17 @@ int main(int argc, const char* argv[]) if( baudrate == 0 ) 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); + if( !open_port(argv[1], baudrate) ) return 1; - mip_interface_init(&device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000); + mip_interface_init( + &device, parse_buffer, sizeof(parse_buffer), mip_timeout_from_baudrate(baudrate), 1000, + &mip_interface_user_send_to_device, &mip_interface_user_recv_from_device, &mip_interface_default_update, NULL + ); + // Record program start time for use with difftime in getTimestamp(). time(&startTime); @@ -150,7 +176,6 @@ int main(int argc, const char* argv[]) enum mip_cmd_result result; // Get the base rate. - volatile uint32_t now = clock(); uint16_t base_rate; result = mip_3dm_get_base_rate(&device, MIP_SENSOR_DATA_DESC_SET, &base_rate); @@ -219,6 +244,40 @@ int main(int argc, const char* argv[]) done: +#ifdef MIP_ENABLE_DIAGNOSTICS + printf( + "\nDiagnostics:\n" + "\n" + "Commands:\n" + " Sent: %" PRIu16 "\n" + " Acks: %" PRIu16 "\n" + " Nacks: %" PRIu16 "\n" + " Timeouts: %" PRIu16 "\n" + " Errors: %" PRIu16 "\n" + "\n" + "Parser:\n" + " Valid packets: %" PRIu32 "\n" + " Invalid packets: %" PRIu32 "\n" + " Timeouts: %" PRIu32 "\n" + "\n" + " Bytes read: %" PRIu32 "\n" + " Valid bytes: %" PRIu32 "\n" + " Unparsed bytes: %" PRIu32 "\n", + mip_cmd_queue_diagnostic_cmds_queued(mip_interface_cmd_queue(&device)), + mip_cmd_queue_diagnostic_cmd_acks(mip_interface_cmd_queue(&device)), + mip_cmd_queue_diagnostic_cmd_nacks(mip_interface_cmd_queue(&device)), + mip_cmd_queue_diagnostic_cmd_timeouts(mip_interface_cmd_queue(&device)), + mip_cmd_queue_diagnostic_cmd_errors(mip_interface_cmd_queue(&device)), + + mip_parser_diagnostic_valid_packets(mip_interface_parser(&device)), + mip_parser_diagnostic_invalid_packets(mip_interface_parser(&device)), + mip_parser_diagnostic_timeouts(mip_interface_parser(&device)), + mip_parser_diagnostic_bytes_read(mip_interface_parser(&device)), + mip_parser_diagnostic_packet_bytes(mip_interface_parser(&device)), + mip_parser_diagnostic_bytes_skipped(mip_interface_parser(&device)) + ); +#endif // MIP_ENABLE_DIAGNOSTICS + serial_port_close(&port); return result == MIP_ACK_OK ? 0 : 2; } diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index 83c9cef80..c071d73f4 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -14,9 +14,12 @@ #include #include +#define __STDC_FORMAT_MACROS 1 +#include + mip::data_sensor::ScaledAccel scaled_accel; -void handlePacket(void*, const mip::Packet& packet, mip::Timestamp timestamp) +void handlePacket(void*, const mip::PacketRef& packet, mip::Timestamp timestamp) { // if(packet.descriptorSet() != mip::MIP_SENSOR_DATA_DESC_SET) // return; @@ -56,19 +59,14 @@ void handleMag(void*, const mip::data_sensor::ScaledMag& data, mip::Timestamp ti } -int main(int argc, const char* argv[]) +int run(mip::DeviceInterface& device) { - try - { - std::unique_ptr utils = handleCommonArgs(argc, argv); - std::unique_ptr& device = utils->device; - mip::CmdResult result; // Get the base rate. uint16_t base_rate; - result = mip::commands_3dm::getBaseRate(*device, mip::data_sensor::DESCRIPTOR_SET, &base_rate); + result = mip::commands_3dm::getBaseRate(device, mip::data_sensor::DESCRIPTOR_SET, &base_rate); if( result != mip::CmdResult::ACK_OK ) return fprintf(stderr, "Failed to get base rate: %s (%d)\n", result.name(), result.value), 1; @@ -84,13 +82,13 @@ int main(int argc, const char* argv[]) { 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, 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, 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; @@ -98,23 +96,23 @@ int main(int argc, const char* argv[]) // Register some callbacks. mip::DispatchHandler packetHandler; - device->registerPacketCallback<&handlePacket>(packetHandler, mip::C::MIP_DISPATCH_ANY_DATA_SET, false); + device.registerPacketCallback<&handlePacket>(packetHandler, mip::C::MIP_DISPATCH_ANY_DATA_SET, false); mip::DispatchHandler dataHandlers[4]; - device->registerFieldCallback<&handleAccel>(dataHandlers[0], mip::data_sensor::DESCRIPTOR_SET, mip::data_sensor::DATA_ACCEL_SCALED); - device->registerDataCallback(dataHandlers[1]); - device->registerDataCallback(dataHandlers[2]); - device->registerExtractor(dataHandlers[3], &scaled_accel); + device.registerFieldCallback<&handleAccel>(dataHandlers[0], mip::data_sensor::DESCRIPTOR_SET, mip::data_sensor::DATA_ACCEL_SCALED); + device.registerDataCallback(dataHandlers[1]); + device.registerDataCallback(dataHandlers[2]); + device.registerExtractor(dataHandlers[3], &scaled_accel); // Enable the data stream and resume the device. - result = mip::commands_3dm::writeDatastreamControl(*device, mip::data_sensor::DESCRIPTOR_SET, true); + result = mip::commands_3dm::writeDatastreamControl(device, mip::data_sensor::DESCRIPTOR_SET, true); if( result != mip::CmdResult::ACK_OK ) return fprintf(stderr, "Failed to enable datastream: %s (%d)\n", result.name(), result.value), 1; // Resume the device to ensure it's streaming. - result = mip::commands_base::resume(*device); + result = mip::commands_base::resume(device); if( result != mip::CmdResult::ACK_OK ) return fprintf(stderr, "Failed to resume device: %s (%d)\n", result.name(), result.value), 1; @@ -122,19 +120,24 @@ int main(int argc, const char* argv[]) const mip::Timestamp start_time = getCurrentTimestamp(); do { - device->update(); + device.update(); std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while( getCurrentTimestamp() - start_time < 3000 ); - result = mip::commands_base::setIdle(*device); + result = mip::commands_base::setIdle(device); if( result != mip::CmdResult::ACK_OK ) return fprintf(stderr, "Failed to idle device: %s (%d)\n", result.name(), result.value), 1; - // mip::TdmCommands::EventControl ctrl; - // ctrl.mode = mip::TdmCommands::EventControl::Mode::ENABLED; + return 0; +} - return 0; +int main(int argc, const char* argv[]) +{ + std::unique_ptr utils; + try + { + utils = handleCommonArgs(argc, argv); } catch(const std::underflow_error& ex) { @@ -145,5 +148,42 @@ int main(int argc, const char* argv[]) fprintf(stderr, "Error: %s\n", ex.what()); return 1; } - return 0; + + const int result = run(*utils->device); + +#ifdef MIP_ENABLE_DIAGNOSTICS + printf( + "\nDiagnostics:\n" + "\n" + "Commands:\n" + " Sent: %" PRIu16 "\n" + " Acks: %" PRIu16 "\n" + " Nacks: %" PRIu16 "\n" + " Timeouts: %" PRIu16 "\n" + " Errors: %" PRIu16 "\n" + "\n" + "Parser:\n" + " Valid packets: %" PRIu32 "\n" + " Invalid packets: %" PRIu32 "\n" + " Timeouts: %" PRIu32 "\n" + "\n" + " Bytes read: %" PRIu32 "\n" + " Valid bytes: %" PRIu32 "\n" + " Unparsed bytes: %" PRIu32 "\n", + mip_cmd_queue_diagnostic_cmds_queued(&utils->device->cmdQueue()), + mip_cmd_queue_diagnostic_cmd_acks(&utils->device->cmdQueue()), + mip_cmd_queue_diagnostic_cmd_nacks(&utils->device->cmdQueue()), + mip_cmd_queue_diagnostic_cmd_timeouts(&utils->device->cmdQueue()), + mip_cmd_queue_diagnostic_cmd_errors(&utils->device->cmdQueue()), + + mip_parser_diagnostic_valid_packets(&utils->device->parser()), + mip_parser_diagnostic_invalid_packets(&utils->device->parser()), + mip_parser_diagnostic_timeouts(&utils->device->parser()), + mip_parser_diagnostic_bytes_read(&utils->device->parser()), + mip_parser_diagnostic_packet_bytes(&utils->device->parser()), + mip_parser_diagnostic_bytes_skipped(&utils->device->parser()) + ); +#endif // MIP_ENABLE_DIAGNOSTICS + + return result; } diff --git a/scripts/release.sh b/scripts/release.sh new file mode 100755 index 000000000..be872ad39 --- /dev/null +++ b/scripts/release.sh @@ -0,0 +1,111 @@ +#!/bin/bash + +# Exit on error +set -ex + +# On Jenkins, log all commands +if [ "${ISHUDSONBUILD}" == "True" ]; then + set -x +fi + +# Get some arguments from the user +generate_notes_flag="" +while [[ $# -gt 0 ]]; do + case $1 in + --artifacts) + artifacts="$2" + shift # past argument + shift # past value + ;; + --docs-zip) + docs_zip="$2" + shift # past argument + shift # past value + ;; + --target) + target="$2" + shift # past argument + shift # past value + ;; + --release) + release_name="$2" + shift # past argument + shift # past value + ;; + --generate-notes) + generate_notes_flag="--generate-notes" + shift # past argument + ;; + *) + shift # past argument + ;; + esac +done +if [ -z "${artifacts}" ] || [ -z "${docs_zip}" ] || [ -z "${release_name}" ] || [ -z "${target}" ]; then + echo "Script must be called with --target, --docs-zip, --artifacts and --release" + exit 1 +fi + +# Some constants and other important variables +repo="LORD-MicroStrain/mip_sdk" +script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" &> /dev/null && pwd)" +project_dir="${script_dir}/.." +tmp_dir="/tmp" +docs_dir="${tmp_dir}/mip_sdk_documentation" +docs_release_dir="${docs_dir}/${release_name}" + +# Find the commit that this project is built on +pushd "${project_dir}" +mip_sdk_commit="$(git rev-parse HEAD)" +popd + +# Generate a release notes file +documentation_link="https://lord-microstrain.github.io/mip_sdk_documentation/${release_name}" +changelog_link="https://github.com/LORD-MicroStrain/mip_sdk/blob/${release_name}/CHANGELOG.md" +release_notes_file="${tmp_dir}/mip-sdk-release-notes-${release_name}.md" +echo "## Useful Links" > ${release_notes_file} +echo "* [Changelog](${changelog_link})" >> ${release_notes_file} +echo "* [Documentation](${documentation_link})" >> ${release_notes_file} + +# Deploy the artifacts to Github +gh release delete \ + -y \ + -R "${repo}" \ + "${release_name}" || echo "No existing release named ${release_name}. Creating now..." +gh release create \ + -R "${repo}" \ + --title "${release_name}" \ + --target "${target}" \ + ${generate_notes_flag} \ + --notes-file "${release_notes_file}" \ + "${release_name}" ${artifacts} +rm -f "${release_notes_file}" + +# Commit the documentation to the github pages branch +rm -rf "${docs_dir}" +git clone -b "main" "https://github.com/LORD-MicroStrain/mip_sdk_documentation.git" "${docs_dir}" +rm -rf "${docs_release_dir}" +mkdir -p "${docs_release_dir}" +pushd "${docs_release_dir}" +unzip "${docs_zip}" -d "${docs_release_dir}" + +# If the tag is not already in the readme, add it +if ! grep -q -E "^\* \[${release_name}\]\(.*\)$" "${docs_dir}/README.md"; then + echo "* [${release_name}](${documentation_link})" >> "${docs_dir}/README.md" +fi + +# Only commit if there are changes +if ! git diff-index --quiet HEAD --; then + git add --all + git commit -m "Adds/updates documentation for release ${release_name} at ${repo}@${mip_sdk_commit}." + + # Set up the auth for github assuming that a valid token is in the environment at "GH_TOKEN" + git_askpass_file="${project_dir}/.mip-sdk-git-askpass" + echo 'echo ${GH_TOKEN}' > "${git_askpass_file}" + chmod 700 "${git_askpass_file}" + GIT_ASKPASS="${git_askpass_file}" git push origin main + rm "${git_askpass_file}" +else + echo "No changes to commit to documentation" +fi +popd diff --git a/src/mip/definitions/commands_3dm.c b/src/mip/definitions/commands_3dm.c index 0748a27e2..8e5708e96 100644 --- a/src/mip/definitions/commands_3dm.c +++ b/src/mip/definitions/commands_3dm.c @@ -99,7 +99,7 @@ void extract_mip_3dm_poll_imu_message_command(mip_serializer* serializer, mip_3d extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, self->num_descriptors); + 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]); @@ -140,7 +140,7 @@ void extract_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, mip_3 extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, self->num_descriptors); + 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]); @@ -181,7 +181,7 @@ void extract_mip_3dm_poll_filter_message_command(mip_serializer* serializer, mip extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, self->num_descriptors); + 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]); @@ -227,7 +227,7 @@ 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, self->num_descriptors); + 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]); @@ -247,7 +247,7 @@ 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, self->num_descriptors); + 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]); @@ -359,7 +359,7 @@ 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, self->num_descriptors); + 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]); @@ -379,7 +379,7 @@ 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, self->num_descriptors); + 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]); @@ -491,7 +491,7 @@ 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, self->num_descriptors); + 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]); @@ -511,7 +511,7 @@ 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, self->num_descriptors); + 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]); @@ -682,7 +682,7 @@ void extract_mip_3dm_poll_data_command(mip_serializer* serializer, mip_3dm_poll_ extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, self->num_descriptors); + 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]); @@ -788,7 +788,7 @@ void extract_mip_3dm_message_format_command(mip_serializer* serializer, mip_3dm_ if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, self->num_descriptors); + 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]); @@ -812,7 +812,7 @@ void extract_mip_3dm_message_format_response(mip_serializer* serializer, mip_3dm extract_u8(serializer, &self->desc_set); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, self->num_descriptors); + 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]); @@ -931,7 +931,7 @@ void extract_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, mip_3dm_ extract_bool(serializer, &self->suppress_ack); assert(self->count); - extract_count(serializer, &self->count, self->count); + 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]); @@ -977,7 +977,7 @@ 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, self->count); + 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]); @@ -997,7 +997,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, self->count); + 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]); @@ -1411,6 +1411,207 @@ 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)mip_serializer_length(&serializer)); } +void insert_mip_3dm_constellation_settings_command(mip_serializer* serializer, const mip_3dm_constellation_settings_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_u16(serializer, self->max_channels); + + 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_command(mip_serializer* serializer, mip_3dm_constellation_settings_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_u16(serializer, &self->max_channels); + + assert(self->config_count); + 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]); + + } +} + +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); + + + 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(mip_serializer* serializer, mip_3dm_constellation_settings_response* self) +{ + extract_u16(serializer, &self->max_channels_available); + + extract_u16(serializer, &self->max_channels_use); + + assert(self->config_count); + 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]); + +} + +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)); +} +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); + *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)); +} +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); + *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); + + 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) +{ + 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); + + 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) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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); + + 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)); + + 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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(max_channels_available_out); + extract_u16(&deserializer, max_channels_available_out); + + assert(max_channels_use_out); + extract_u16(&deserializer, max_channels_use_out); + + assert(config_count_out); + 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 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_3dm_save_constellation_settings(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} void insert_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1440,7 +1641,7 @@ void extract_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, mip_ extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, &self->sbas_options); assert(self->num_included_prns); - extract_count(serializer, &self->num_included_prns, self->num_included_prns); + 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]); @@ -1468,7 +1669,7 @@ void extract_mip_3dm_gnss_sbas_settings_response(mip_serializer* serializer, mip extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, &self->sbas_options); assert(self->num_included_prns); - extract_count(serializer, &self->num_included_prns, self->num_included_prns); + 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]); @@ -1580,6 +1781,138 @@ 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)mip_serializer_length(&serializer)); } +void insert_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, self->option); + + insert_u8(serializer, self->flags); + + } +} +void extract_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, mip_3dm_gnss_assisted_fix_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, &self->option); + + extract_u8(serializer, &self->flags); + + } +} + +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); + +} +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); + +} + +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)); +} +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); + *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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(&serializer, option); + + insert_u8(&serializer, flags); + + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(option_out); + extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(&deserializer, option_out); + + assert(flags_out); + extract_u8(&deserializer, flags_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_3dm_save_gnss_assisted_fix(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} void insert_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1678,7 +2011,7 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d } return result; } -void insert_mip_3dm_adv_lowpass_filter_command(mip_serializer* serializer, const mip_3dm_adv_lowpass_filter_command* self) +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); @@ -1696,7 +2029,7 @@ void insert_mip_3dm_adv_lowpass_filter_command(mip_serializer* serializer, const } } -void extract_mip_3dm_adv_lowpass_filter_command(mip_serializer* serializer, mip_3dm_adv_lowpass_filter_command* self) +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); @@ -1715,7 +2048,7 @@ void extract_mip_3dm_adv_lowpass_filter_command(mip_serializer* serializer, mip_ } } -void insert_mip_3dm_adv_lowpass_filter_response(mip_serializer* serializer, const mip_3dm_adv_lowpass_filter_response* self) +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); @@ -1728,7 +2061,7 @@ void insert_mip_3dm_adv_lowpass_filter_response(mip_serializer* serializer, cons insert_u8(serializer, self->reserved); } -void extract_mip_3dm_adv_lowpass_filter_response(mip_serializer* serializer, mip_3dm_adv_lowpass_filter_response* self) +void extract_mip_3dm_imu_lowpass_filter_response(mip_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self) { extract_u8(serializer, &self->target_descriptor); @@ -1742,7 +2075,7 @@ void extract_mip_3dm_adv_lowpass_filter_response(mip_serializer* serializer, mip } -mip_cmd_result mip_3dm_write_adv_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(struct mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1762,9 +2095,9 @@ mip_cmd_result mip_3dm_write_adv_lowpass_filter(struct mip_interface* device, ui assert(mip_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ADVANCED_DATA_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)mip_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_adv_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(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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1777,7 +2110,7 @@ mip_cmd_result mip_3dm_read_adv_lowpass_filter(struct mip_interface* device, uin assert(mip_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_ADVANCED_DATA_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)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_ADVANCED_DATA_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1803,7 +2136,7 @@ mip_cmd_result mip_3dm_read_adv_lowpass_filter(struct mip_interface* device, uin } return result; } -mip_cmd_result mip_3dm_save_adv_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) +mip_cmd_result mip_3dm_save_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1815,9 +2148,9 @@ mip_cmd_result mip_3dm_save_adv_lowpass_filter(struct mip_interface* device, uin assert(mip_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ADVANCED_DATA_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)mip_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_adv_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_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1829,9 +2162,9 @@ mip_cmd_result mip_3dm_load_adv_lowpass_filter(struct mip_interface* device, uin assert(mip_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ADVANCED_DATA_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)mip_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_adv_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_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1843,7 +2176,7 @@ mip_cmd_result mip_3dm_default_adv_lowpass_filter(struct mip_interface* device, assert(mip_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ADVANCED_DATA_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)mip_serializer_length(&serializer)); } void insert_mip_3dm_pps_source_command(mip_serializer* serializer, const mip_3dm_pps_source_command* self) { @@ -2419,7 +2752,7 @@ void extract_mip_3dm_get_event_support_response(mip_serializer* serializer, mip_ extract_u8(serializer, &self->max_instances); assert(self->num_entries); - extract_count(serializer, &self->num_entries, self->num_entries); + 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]); @@ -2638,7 +2971,7 @@ void insert_mip_3dm_get_event_trigger_status_command(mip_serializer* serializer, 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, self->requested_count); + 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]); @@ -2657,7 +2990,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, self->count); + 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]); @@ -2736,7 +3069,7 @@ void insert_mip_3dm_get_event_action_status_command(mip_serializer* serializer, 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, self->requested_count); + 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]); @@ -2755,7 +3088,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, self->count); + 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]); @@ -3291,7 +3624,7 @@ void extract_mip_3dm_event_action_command_message_params(mip_serializer* seriali extract_u16(serializer, &self->decimation); assert(self->num_fields); - extract_count(serializer, &self->num_fields, self->num_fields); + 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]); @@ -3933,6 +4266,114 @@ 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)mip_serializer_length(&serializer)); } +void insert_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_bool(serializer, self->enable); + + } +} +void extract_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, mip_3dm_coning_sculling_enable_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + 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); + +} +void extract_mip_3dm_coning_sculling_enable_response(mip_serializer* serializer, mip_3dm_coning_sculling_enable_response* self) +{ + extract_bool(serializer, &self->enable); + +} + +mip_cmd_result mip_3dm_write_coning_sculling_enable(struct mip_interface* device, bool enable) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_bool(&serializer, enable); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, bool* enable_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(enable_out); + extract_bool(&deserializer, enable_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_3dm_save_coning_sculling_enable(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4599,7 +5040,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, self->num_ranges); + 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]); @@ -4653,6 +5094,180 @@ 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) +{ + insert_mip_function_selector(serializer, self->function); + + insert_u8(serializer, self->desc_set); + + 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); + + } +} +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); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_bool(serializer, &self->enable); + + extract_bool(serializer, &self->manual); + + 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); + +} +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); + +} + +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + 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)); + + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)mip_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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + insert_u8(&serializer, desc_set); + + insert_u8(&serializer, field_desc); + + assert(mip_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); + + 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); + + assert(enable_out); + extract_bool(&deserializer, enable_out); + + assert(manual_out); + extract_bool(&deserializer, manual_out); + + assert(frequency_out); + extract_float(&deserializer, frequency_out); + + if( mip_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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + insert_u8(&serializer, desc_set); + + insert_u8(&serializer, field_desc); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_load_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + insert_u8(&serializer, desc_set); + + insert_u8(&serializer, field_desc); + + assert(mip_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)); +} +mip_cmd_result mip_3dm_default_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + insert_u8(&serializer, desc_set); + + insert_u8(&serializer, field_desc); + + assert(mip_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)); +} #ifdef __cplusplus } // namespace C diff --git a/src/mip/definitions/commands_3dm.cpp b/src/mip/definitions/commands_3dm.cpp index fb98d603c..477119d41 100644 --- a/src/mip/definitions/commands_3dm.cpp +++ b/src/mip/definitions/commands_3dm.cpp @@ -66,13 +66,13 @@ void extract(Serializer& serializer, PollImuMessage& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) +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)); @@ -103,13 +103,13 @@ void extract(Serializer& serializer, PollGnssMessage& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) +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)); @@ -140,13 +140,13 @@ void extract(Serializer& serializer, PollFilterMessage& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) +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)); @@ -182,7 +182,7 @@ void extract(Serializer& serializer, ImuMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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,13 +199,13 @@ void insert(Serializer& serializer, const ImuMessageFormat::Response& self) } void extract(Serializer& serializer, ImuMessageFormat::Response& self) { - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) +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)); @@ -221,7 +221,7 @@ CmdResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) +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)); @@ -230,7 +230,7 @@ CmdResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptors assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -246,7 +246,7 @@ CmdResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptors } return result; } -CmdResult saveImuMessageFormat(C::mip_interface& device) +TypedResult saveImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -256,7 +256,7 @@ CmdResult saveImuMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadImuMessageFormat(C::mip_interface& device) +TypedResult loadImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -266,7 +266,7 @@ CmdResult loadImuMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultImuMessageFormat(C::mip_interface& device) +TypedResult defaultImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -295,7 +295,7 @@ void extract(Serializer& serializer, GpsMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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,13 +312,13 @@ void insert(Serializer& serializer, const GpsMessageFormat::Response& self) } void extract(Serializer& serializer, GpsMessageFormat::Response& self) { - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) +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)); @@ -334,7 +334,7 @@ CmdResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) +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)); @@ -343,7 +343,7 @@ CmdResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptors assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -359,7 +359,7 @@ CmdResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptors } return result; } -CmdResult saveGpsMessageFormat(C::mip_interface& device) +TypedResult saveGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -369,7 +369,7 @@ CmdResult saveGpsMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadGpsMessageFormat(C::mip_interface& device) +TypedResult loadGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -379,7 +379,7 @@ CmdResult loadGpsMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultGpsMessageFormat(C::mip_interface& device) +TypedResult defaultGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -408,7 +408,7 @@ void extract(Serializer& serializer, FilterMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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,13 +425,13 @@ void insert(Serializer& serializer, const FilterMessageFormat::Response& self) } void extract(Serializer& serializer, FilterMessageFormat::Response& self) { - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) +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)); @@ -447,7 +447,7 @@ CmdResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescript return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) +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)); @@ -456,7 +456,7 @@ CmdResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescript assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -472,7 +472,7 @@ CmdResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescript } return result; } -CmdResult saveFilterMessageFormat(C::mip_interface& device) +TypedResult saveFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -482,7 +482,7 @@ CmdResult saveFilterMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadFilterMessageFormat(C::mip_interface& device) +TypedResult loadFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -492,7 +492,7 @@ CmdResult loadFilterMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultFilterMessageFormat(C::mip_interface& device) +TypedResult defaultFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -524,12 +524,12 @@ void extract(Serializer& serializer, ImuGetBaseRate::Response& self) } -CmdResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut) +TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMU_BASE_RATE, NULL, 0, REPLY_IMU_BASE_RATE, buffer, &responseLength); + 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 ) { @@ -565,12 +565,12 @@ void extract(Serializer& serializer, GpsGetBaseRate::Response& self) } -CmdResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut) +TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_GNSS_BASE_RATE, NULL, 0, REPLY_GNSS_BASE_RATE, buffer, &responseLength); + 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 ) { @@ -606,12 +606,12 @@ void extract(Serializer& serializer, FilterGetBaseRate::Response& self) } -CmdResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut) +TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_FILTER_BASE_RATE, NULL, 0, REPLY_FILTER_BASE_RATE, buffer, &responseLength); + 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 ) { @@ -643,13 +643,13 @@ void extract(Serializer& serializer, PollData& self) extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors) +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)); @@ -694,7 +694,7 @@ void extract(Serializer& serializer, GetBaseRate::Response& self) } -CmdResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut) +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)); @@ -704,7 +704,7 @@ CmdResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateO assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_BASE_RATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -743,7 +743,7 @@ void extract(Serializer& serializer, MessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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,13 +764,13 @@ void extract(Serializer& serializer, MessageFormat::Response& self) { extract(serializer, self.desc_set); - C::extract_count(&serializer, &self.num_descriptors, self.num_descriptors); + C::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]); } -CmdResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors) +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)); @@ -788,7 +788,7 @@ CmdResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) +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)); @@ -799,7 +799,7 @@ CmdResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -817,7 +817,7 @@ CmdResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* } return result; } -CmdResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) +TypedResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -829,7 +829,7 @@ CmdResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) +TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -841,7 +841,7 @@ CmdResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) +TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -867,13 +867,13 @@ void extract(Serializer& serializer, NmeaPollData& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.count, self.count); + C::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]); } -CmdResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries) +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)); @@ -909,7 +909,7 @@ void extract(Serializer& serializer, NmeaMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.count, self.count); + C::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,13 +926,13 @@ void insert(Serializer& serializer, const NmeaMessageFormat::Response& self) } void extract(Serializer& serializer, NmeaMessageFormat::Response& self) { - C::extract_count(&serializer, &self.count, self.count); + C::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]); } -CmdResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries) +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)); @@ -948,7 +948,7 @@ CmdResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) +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)); @@ -957,7 +957,7 @@ CmdResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -973,7 +973,7 @@ CmdResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uin } return result; } -CmdResult saveNmeaMessageFormat(C::mip_interface& device) +TypedResult saveNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -983,7 +983,7 @@ CmdResult saveNmeaMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadNmeaMessageFormat(C::mip_interface& device) +TypedResult loadNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -993,7 +993,7 @@ CmdResult loadNmeaMessageFormat(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultNmeaMessageFormat(C::mip_interface& device) +TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1014,7 +1014,7 @@ void extract(Serializer& serializer, DeviceSettings& self) } -CmdResult saveDeviceSettings(C::mip_interface& device) +TypedResult saveDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1024,7 +1024,7 @@ CmdResult saveDeviceSettings(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadDeviceSettings(C::mip_interface& device) +TypedResult loadDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1034,7 +1034,7 @@ CmdResult loadDeviceSettings(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultDeviceSettings(C::mip_interface& device) +TypedResult defaultDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1076,7 +1076,7 @@ void extract(Serializer& serializer, UartBaudrate::Response& self) } -CmdResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) +TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1088,7 +1088,7 @@ CmdResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) +TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1097,7 +1097,7 @@ CmdResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_UART_BAUDRATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1111,7 +1111,7 @@ CmdResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) } return result; } -CmdResult saveUartBaudrate(C::mip_interface& device) +TypedResult saveUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1121,7 +1121,7 @@ CmdResult saveUartBaudrate(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadUartBaudrate(C::mip_interface& device) +TypedResult loadUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1131,7 +1131,7 @@ CmdResult loadUartBaudrate(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultUartBaudrate(C::mip_interface& device) +TypedResult defaultUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1156,7 +1156,7 @@ void extract(Serializer& serializer, FactoryStreaming& self) } -CmdResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved) +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)); @@ -1209,7 +1209,7 @@ void extract(Serializer& serializer, DatastreamControl::Response& self) } -CmdResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) +TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1223,7 +1223,7 @@ CmdResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) +TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1234,7 +1234,7 @@ CmdResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1250,7 +1250,7 @@ CmdResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* } return result; } -CmdResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) +TypedResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1262,7 +1262,7 @@ CmdResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) +TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1274,7 +1274,7 @@ CmdResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) +TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1286,6 +1286,166 @@ CmdResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); } +void insert(Serializer& serializer, const ConstellationSettings& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.max_channels); + + insert(serializer, self.config_count); + + for(unsigned int i=0; i < self.config_count; i++) + insert(serializer, self.settings[i]); + + } +} +void extract(Serializer& serializer, ConstellationSettings& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.max_channels); + + C::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(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(Serializer& serializer, ConstellationSettings::Response& self) +{ + extract(serializer, self.max_channels_available); + + extract(serializer, self.max_channels_use); + + C::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(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(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, maxChannels); + + insert(serializer, configCount); + + assert(settings || (configCount == 0)); + for(unsigned int i=0; i < configCount; i++) + insert(serializer, settings[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +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)); + + 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)mip_serializer_length(&serializer), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(maxChannelsAvailableOut); + extract(deserializer, *maxChannelsAvailableOut); + + assert(maxChannelsUseOut); + extract(deserializer, *maxChannelsUseOut); + + C::extract_count(&deserializer, configCountOut, configCountOutMax); + assert(settingsOut || (configCountOut == 0)); + for(unsigned int i=0; i < *configCountOut; i++) + extract(deserializer, settingsOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveConstellationSettings(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadConstellationSettings(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultConstellationSettings(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} void insert(Serializer& serializer, const GnssSbasSettings& self) { insert(serializer, self.function); @@ -1313,7 +1473,7 @@ void extract(Serializer& serializer, GnssSbasSettings& self) extract(serializer, self.sbas_options); - C::extract_count(&serializer, &self.num_included_prns, self.num_included_prns); + C::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]); @@ -1338,13 +1498,13 @@ void extract(Serializer& serializer, GnssSbasSettings::Response& self) extract(serializer, self.sbas_options); - C::extract_count(&serializer, &self.num_included_prns, self.num_included_prns); + C::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]); } -CmdResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns) +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)); @@ -1364,7 +1524,7 @@ CmdResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, Gn return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) +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)); @@ -1373,7 +1533,7 @@ CmdResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1395,7 +1555,7 @@ CmdResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, } return result; } -CmdResult saveGnssSbasSettings(C::mip_interface& device) +TypedResult saveGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1405,7 +1565,7 @@ CmdResult saveGnssSbasSettings(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadGnssSbasSettings(C::mip_interface& device) +TypedResult loadGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1415,7 +1575,7 @@ CmdResult loadGnssSbasSettings(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultGnssSbasSettings(C::mip_interface& device) +TypedResult defaultGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1425,6 +1585,116 @@ CmdResult defaultGnssSbasSettings(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } +void insert(Serializer& serializer, const GnssAssistedFix& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.option); + + insert(serializer, self.flags); + + } +} +void extract(Serializer& serializer, GnssAssistedFix& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.option); + + extract(serializer, self.flags); + + } +} + +void insert(Serializer& serializer, const GnssAssistedFix::Response& self) +{ + insert(serializer, self.option); + + insert(serializer, self.flags); + +} +void extract(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, option); + + insert(serializer, flags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +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)); + + 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)mip_serializer_length(&serializer), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(optionOut); + extract(deserializer, *optionOut); + + assert(flagsOut); + extract(deserializer, *flagsOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveGnssAssistedFix(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadGnssAssistedFix(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultGnssAssistedFix(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} void insert(Serializer& serializer, const GnssTimeAssistance& self) { insert(serializer, self.function); @@ -1473,7 +1743,7 @@ void extract(Serializer& serializer, GnssTimeAssistance::Response& self) } -CmdResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy) +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)); @@ -1489,7 +1759,7 @@ CmdResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) +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)); @@ -1498,7 +1768,7 @@ CmdResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint1 assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1518,7 +1788,7 @@ CmdResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint1 } return result; } -void insert(Serializer& serializer, const AdvLowpassFilter& self) +void insert(Serializer& serializer, const ImuLowpassFilter& self) { insert(serializer, self.function); @@ -1536,7 +1806,7 @@ void insert(Serializer& serializer, const AdvLowpassFilter& self) } } -void extract(Serializer& serializer, AdvLowpassFilter& self) +void extract(Serializer& serializer, ImuLowpassFilter& self) { extract(serializer, self.function); @@ -1555,7 +1825,7 @@ void extract(Serializer& serializer, AdvLowpassFilter& self) } } -void insert(Serializer& serializer, const AdvLowpassFilter::Response& self) +void insert(Serializer& serializer, const ImuLowpassFilter::Response& self) { insert(serializer, self.target_descriptor); @@ -1568,7 +1838,7 @@ void insert(Serializer& serializer, const AdvLowpassFilter::Response& self) insert(serializer, self.reserved); } -void extract(Serializer& serializer, AdvLowpassFilter::Response& self) +void extract(Serializer& serializer, ImuLowpassFilter::Response& self) { extract(serializer, self.target_descriptor); @@ -1582,7 +1852,7 @@ void extract(Serializer& serializer, AdvLowpassFilter::Response& self) } -CmdResult writeAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t 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]; Serializer serializer(buffer, sizeof(buffer)); @@ -1600,9 +1870,9 @@ CmdResult writeAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescript assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADVANCED_DATA_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) +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)); @@ -1613,7 +1883,7 @@ CmdResult readAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescripto assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADVANCED_DATA_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)mip_serializer_length(&serializer), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1638,7 +1908,7 @@ CmdResult readAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescripto } return result; } -CmdResult saveAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) +TypedResult saveImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1648,9 +1918,9 @@ CmdResult saveAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescripto assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADVANCED_DATA_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) +TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1660,9 +1930,9 @@ CmdResult loadAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescripto assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADVANCED_DATA_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) +TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1672,7 +1942,7 @@ CmdResult defaultAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescri assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADVANCED_DATA_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); } void insert(Serializer& serializer, const PpsSource& self) { @@ -1706,7 +1976,7 @@ void extract(Serializer& serializer, PpsSource::Response& self) } -CmdResult writePpsSource(C::mip_interface& device, PpsSource::Source source) +TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1718,7 +1988,7 @@ CmdResult writePpsSource(C::mip_interface& device, PpsSource::Source source) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) +TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1727,7 +1997,7 @@ CmdResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_PPS_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1741,7 +2011,7 @@ CmdResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) } return result; } -CmdResult savePpsSource(C::mip_interface& device) +TypedResult savePpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1751,7 +2021,7 @@ CmdResult savePpsSource(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadPpsSource(C::mip_interface& device) +TypedResult loadPpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1761,7 +2031,7 @@ CmdResult loadPpsSource(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultPpsSource(C::mip_interface& device) +TypedResult defaultPpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1827,7 +2097,7 @@ void extract(Serializer& serializer, GpioConfig::Response& self) } -CmdResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode) +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)); @@ -1845,7 +2115,7 @@ CmdResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Fea return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) +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)); @@ -1856,7 +2126,7 @@ CmdResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feat assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GPIO_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1878,7 +2148,7 @@ CmdResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feat } return result; } -CmdResult saveGpioConfig(C::mip_interface& device, uint8_t pin) +TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1890,7 +2160,7 @@ CmdResult saveGpioConfig(C::mip_interface& device, uint8_t pin) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadGpioConfig(C::mip_interface& device, uint8_t pin) +TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1902,7 +2172,7 @@ CmdResult loadGpioConfig(C::mip_interface& device, uint8_t pin) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) +TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1960,7 +2230,7 @@ void extract(Serializer& serializer, GpioState::Response& self) } -CmdResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) +TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1974,7 +2244,7 @@ CmdResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) +TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1985,7 +2255,7 @@ CmdResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GPIO_STATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2049,7 +2319,7 @@ void extract(Serializer& serializer, Odometer::Response& self) } -CmdResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty) +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)); @@ -2065,7 +2335,7 @@ CmdResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float sca return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) +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)); @@ -2074,7 +2344,7 @@ CmdResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_ODOMETER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2094,7 +2364,7 @@ CmdResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* } return result; } -CmdResult saveOdometer(C::mip_interface& device) +TypedResult saveOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2104,7 +2374,7 @@ CmdResult saveOdometer(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadOdometer(C::mip_interface& device) +TypedResult loadOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2114,7 +2384,7 @@ CmdResult loadOdometer(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultOdometer(C::mip_interface& device) +TypedResult defaultOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2153,7 +2423,7 @@ void extract(Serializer& serializer, GetEventSupport::Response& self) extract(serializer, self.max_instances); - C::extract_count(&serializer, &self.num_entries, self.num_entries); + C::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]); @@ -2174,7 +2444,7 @@ void extract(Serializer& serializer, GetEventSupport::Info& self) } -CmdResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut) +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)); @@ -2184,7 +2454,7 @@ CmdResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_EVENT_SUPPORT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2245,7 +2515,7 @@ void extract(Serializer& serializer, EventControl::Response& self) } -CmdResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode) +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)); @@ -2259,7 +2529,7 @@ CmdResult writeEventControl(C::mip_interface& device, uint8_t instance, EventCon return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) +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)); @@ -2270,7 +2540,7 @@ CmdResult readEventControl(C::mip_interface& device, uint8_t instance, EventCont assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_EVENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2286,7 +2556,7 @@ CmdResult readEventControl(C::mip_interface& device, uint8_t instance, EventCont } return result; } -CmdResult saveEventControl(C::mip_interface& device, uint8_t instance) +TypedResult saveEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2298,7 +2568,7 @@ CmdResult saveEventControl(C::mip_interface& device, uint8_t instance) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadEventControl(C::mip_interface& device, uint8_t instance) +TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2310,7 +2580,7 @@ CmdResult loadEventControl(C::mip_interface& device, uint8_t instance) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultEventControl(C::mip_interface& device, uint8_t instance) +TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2332,7 +2602,7 @@ void insert(Serializer& serializer, const GetEventTriggerStatus& self) } void extract(Serializer& serializer, GetEventTriggerStatus& self) { - C::extract_count(&serializer, &self.requested_count, self.requested_count); + 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++) extract(serializer, self.requested_instances[i]); @@ -2348,7 +2618,7 @@ void insert(Serializer& serializer, const GetEventTriggerStatus::Response& self) } void extract(Serializer& serializer, GetEventTriggerStatus::Response& self) { - C::extract_count(&serializer, &self.count, self.count); + C::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]); @@ -2369,7 +2639,7 @@ void extract(Serializer& serializer, GetEventTriggerStatus::Entry& self) } -CmdResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) +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)); @@ -2383,7 +2653,7 @@ CmdResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2409,7 +2679,7 @@ void insert(Serializer& serializer, const GetEventActionStatus& self) } void extract(Serializer& serializer, GetEventActionStatus& self) { - C::extract_count(&serializer, &self.requested_count, self.requested_count); + 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++) extract(serializer, self.requested_instances[i]); @@ -2425,7 +2695,7 @@ void insert(Serializer& serializer, const GetEventActionStatus::Response& self) } void extract(Serializer& serializer, GetEventActionStatus::Response& self) { - C::extract_count(&serializer, &self.count, self.count); + C::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]); @@ -2446,7 +2716,7 @@ void extract(Serializer& serializer, GetEventActionStatus::Entry& self) } -CmdResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut) +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)); @@ -2460,7 +2730,7 @@ CmdResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2671,7 +2941,7 @@ void extract(Serializer& serializer, EventTrigger::CombinationParams& self) } -CmdResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters) +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)); @@ -2700,7 +2970,7 @@ CmdResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTri return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) +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)); @@ -2711,7 +2981,7 @@ CmdResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrig assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2742,7 +3012,7 @@ CmdResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrig } return result; } -CmdResult saveEventTrigger(C::mip_interface& device, uint8_t instance) +TypedResult saveEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2754,7 +3024,7 @@ CmdResult saveEventTrigger(C::mip_interface& device, uint8_t instance) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadEventTrigger(C::mip_interface& device, uint8_t instance) +TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2766,7 +3036,7 @@ CmdResult loadEventTrigger(C::mip_interface& device, uint8_t instance) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) +TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2899,13 +3169,13 @@ void extract(Serializer& serializer, EventAction::MessageParams& self) extract(serializer, self.decimation); - C::extract_count(&serializer, &self.num_fields, self.num_fields); + C::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]); } -CmdResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters) +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)); @@ -2931,7 +3201,7 @@ CmdResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) +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)); @@ -2942,7 +3212,7 @@ CmdResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* t assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2971,7 +3241,7 @@ CmdResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* t } return result; } -CmdResult saveEventAction(C::mip_interface& device, uint8_t instance) +TypedResult saveEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2983,7 +3253,7 @@ CmdResult saveEventAction(C::mip_interface& device, uint8_t instance) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadEventAction(C::mip_interface& device, uint8_t instance) +TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2995,7 +3265,7 @@ CmdResult loadEventAction(C::mip_interface& device, uint8_t instance) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultEventAction(C::mip_interface& device, uint8_t instance) +TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3043,7 +3313,7 @@ void extract(Serializer& serializer, AccelBias::Response& self) } -CmdResult writeAccelBias(C::mip_interface& device, const float* bias) +TypedResult writeAccelBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3057,7 +3327,7 @@ CmdResult writeAccelBias(C::mip_interface& device, const float* bias) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAccelBias(C::mip_interface& device, float* biasOut) +TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3066,7 +3336,7 @@ CmdResult readAccelBias(C::mip_interface& device, float* biasOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3081,7 +3351,7 @@ CmdResult readAccelBias(C::mip_interface& device, float* biasOut) } return result; } -CmdResult saveAccelBias(C::mip_interface& device) +TypedResult saveAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3091,7 +3361,7 @@ CmdResult saveAccelBias(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAccelBias(C::mip_interface& device) +TypedResult loadAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3101,7 +3371,7 @@ CmdResult loadAccelBias(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAccelBias(C::mip_interface& device) +TypedResult defaultAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3147,7 +3417,7 @@ void extract(Serializer& serializer, GyroBias::Response& self) } -CmdResult writeGyroBias(C::mip_interface& device, const float* bias) +TypedResult writeGyroBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3161,7 +3431,7 @@ CmdResult writeGyroBias(C::mip_interface& device, const float* bias) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGyroBias(C::mip_interface& device, float* biasOut) +TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3170,7 +3440,7 @@ CmdResult readGyroBias(C::mip_interface& device, float* biasOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3185,7 +3455,7 @@ CmdResult readGyroBias(C::mip_interface& device, float* biasOut) } return result; } -CmdResult saveGyroBias(C::mip_interface& device) +TypedResult saveGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3195,7 +3465,7 @@ CmdResult saveGyroBias(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadGyroBias(C::mip_interface& device) +TypedResult loadGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3205,7 +3475,7 @@ CmdResult loadGyroBias(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultGyroBias(C::mip_interface& device) +TypedResult defaultGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3239,7 +3509,7 @@ void extract(Serializer& serializer, CaptureGyroBias::Response& self) } -CmdResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) +TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3249,7 +3519,7 @@ CmdResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, fl assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3300,7 +3570,7 @@ void extract(Serializer& serializer, MagHardIronOffset::Response& self) } -CmdResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) +TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3314,7 +3584,7 @@ CmdResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) +TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3323,7 +3593,7 @@ CmdResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3338,7 +3608,7 @@ CmdResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) } return result; } -CmdResult saveMagHardIronOffset(C::mip_interface& device) +TypedResult saveMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3348,7 +3618,7 @@ CmdResult saveMagHardIronOffset(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadMagHardIronOffset(C::mip_interface& device) +TypedResult loadMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3358,7 +3628,7 @@ CmdResult loadMagHardIronOffset(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultMagHardIronOffset(C::mip_interface& device) +TypedResult defaultMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3404,7 +3674,7 @@ void extract(Serializer& serializer, MagSoftIronMatrix::Response& self) } -CmdResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) +TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3418,7 +3688,7 @@ CmdResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) +TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3427,7 +3697,7 @@ CmdResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3442,7 +3712,7 @@ CmdResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) } return result; } -CmdResult saveMagSoftIronMatrix(C::mip_interface& device) +TypedResult saveMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3452,7 +3722,7 @@ CmdResult saveMagSoftIronMatrix(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadMagSoftIronMatrix(C::mip_interface& device) +TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3462,7 +3732,7 @@ CmdResult loadMagSoftIronMatrix(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultMagSoftIronMatrix(C::mip_interface& device) +TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3472,6 +3742,103 @@ CmdResult defaultMagSoftIronMatrix(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); } +void insert(Serializer& serializer, const ConingScullingEnable& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.enable); + + } +} +void extract(Serializer& serializer, ConingScullingEnable& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.enable); + + } +} + +void insert(Serializer& serializer, const ConingScullingEnable::Response& self) +{ + insert(serializer, self.enable); + +} +void extract(Serializer& serializer, ConingScullingEnable::Response& self) +{ + extract(serializer, self.enable); + +} + +TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(enableOut); + extract(deserializer, *enableOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveConingScullingEnable(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadConingScullingEnable(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultConingScullingEnable(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} void insert(Serializer& serializer, const Sensor2VehicleTransformEuler& self) { insert(serializer, self.function); @@ -3520,7 +3887,7 @@ void extract(Serializer& serializer, Sensor2VehicleTransformEuler::Response& sel } -CmdResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw) +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)); @@ -3536,7 +3903,7 @@ CmdResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) +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)); @@ -3545,7 +3912,7 @@ CmdResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* roll assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3565,7 +3932,7 @@ CmdResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* roll } return result; } -CmdResult saveSensor2VehicleTransformEuler(C::mip_interface& device) +TypedResult saveSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3575,7 +3942,7 @@ CmdResult saveSensor2VehicleTransformEuler(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensor2VehicleTransformEuler(C::mip_interface& device) +TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3585,7 +3952,7 @@ CmdResult loadSensor2VehicleTransformEuler(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) +TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3631,7 +3998,7 @@ void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion::Response } -CmdResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) +TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3645,7 +4012,7 @@ CmdResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) +TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3654,7 +4021,7 @@ CmdResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3669,7 +4036,7 @@ CmdResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* } return result; } -CmdResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) +TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3679,7 +4046,7 @@ CmdResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) +TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3689,7 +4056,7 @@ CmdResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) +TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3735,7 +4102,7 @@ void extract(Serializer& serializer, Sensor2VehicleTransformDcm::Response& self) } -CmdResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) +TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3749,7 +4116,7 @@ CmdResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) +TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3758,7 +4125,7 @@ CmdResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3773,7 +4140,7 @@ CmdResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut } return result; } -CmdResult saveSensor2VehicleTransformDcm(C::mip_interface& device) +TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3783,7 +4150,7 @@ CmdResult saveSensor2VehicleTransformDcm(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensor2VehicleTransformDcm(C::mip_interface& device) +TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3793,7 +4160,7 @@ CmdResult loadSensor2VehicleTransformDcm(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) +TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3859,7 +4226,7 @@ void extract(Serializer& serializer, ComplementaryFilter::Response& self) } -CmdResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant) +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)); @@ -3877,7 +4244,7 @@ CmdResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnabl return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) +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)); @@ -3886,7 +4253,7 @@ CmdResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnabl assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3909,7 +4276,7 @@ CmdResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnabl } return result; } -CmdResult saveComplementaryFilter(C::mip_interface& device) +TypedResult saveComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3919,7 +4286,7 @@ CmdResult saveComplementaryFilter(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadComplementaryFilter(C::mip_interface& device) +TypedResult loadComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3929,7 +4296,7 @@ CmdResult loadComplementaryFilter(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultComplementaryFilter(C::mip_interface& device) +TypedResult defaultComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3979,7 +4346,7 @@ void extract(Serializer& serializer, SensorRange::Response& self) } -CmdResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) +TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3993,7 +4360,7 @@ CmdResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uin return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) +TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -4004,7 +4371,7 @@ CmdResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR_RANGE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4020,7 +4387,7 @@ CmdResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint } return result; } -CmdResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) +TypedResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -4032,7 +4399,7 @@ CmdResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) +TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -4044,7 +4411,7 @@ CmdResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) +TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -4081,7 +4448,7 @@ void extract(Serializer& serializer, CalibratedSensorRanges::Response& self) { extract(serializer, self.sensor); - C::extract_count(&serializer, &self.num_ranges, self.num_ranges); + C::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]); @@ -4102,7 +4469,7 @@ void extract(Serializer& serializer, CalibratedSensorRanges::Entry& self) } -CmdResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut) +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)); @@ -4112,7 +4479,7 @@ CmdResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType senso assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_CALIBRATED_RANGES, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4130,6 +4497,169 @@ CmdResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType senso } return result; } +void insert(Serializer& serializer, const LowpassFilter& self) +{ + insert(serializer, self.function); + + insert(serializer, self.desc_set); + + insert(serializer, self.field_desc); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.enable); + + insert(serializer, self.manual); + + insert(serializer, self.frequency); + + } +} +void extract(Serializer& serializer, LowpassFilter& self) +{ + extract(serializer, self.function); + + extract(serializer, self.desc_set); + + extract(serializer, self.field_desc); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.enable); + + extract(serializer, self.manual); + + extract(serializer, self.frequency); + + } +} + +void insert(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(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, descSet); + + insert(serializer, fieldDesc); + + insert(serializer, enable); + + insert(serializer, manual); + + insert(serializer, frequency); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +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)); + + insert(serializer, FunctionSelector::READ); + insert(serializer, descSet); + + insert(serializer, 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)mip_serializer_length(&serializer), REPLY_LOWPASS_FILTER, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + extract(deserializer, descSet); + + extract(deserializer, fieldDesc); + + assert(enableOut); + extract(deserializer, *enableOut); + + assert(manualOut); + extract(deserializer, *manualOut); + + assert(frequencyOut); + extract(deserializer, *frequencyOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +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)); + + insert(serializer, FunctionSelector::SAVE); + insert(serializer, descSet); + + insert(serializer, fieldDesc); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +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)); + + insert(serializer, FunctionSelector::LOAD); + insert(serializer, descSet); + + insert(serializer, fieldDesc); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +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)); + + insert(serializer, FunctionSelector::RESET); + insert(serializer, descSet); + + insert(serializer, fieldDesc); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); +} } // namespace commands_3dm } // namespace mip diff --git a/src/mip/definitions/commands_3dm.h b/src/mip/definitions/commands_3dm.h index afec6326c..c2e3b7925 100644 --- a/src/mip/definitions/commands_3dm.h +++ b/src/mip/definitions/commands_3dm.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -79,10 +80,11 @@ enum MIP_CMD_DESC_3DM_GPIO_CONFIG = 0x41, MIP_CMD_DESC_3DM_GPIO_STATE = 0x42, MIP_CMD_DESC_3DM_ODOMETER_CONFIG = 0x43, - MIP_CMD_DESC_3DM_ADVANCED_DATA_FILTER = 0x50, + MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER = 0x50, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER = 0x51, MIP_CMD_DESC_3DM_SENSOR_RANGE = 0x52, MIP_CMD_DESC_3DM_CALIBRATED_RANGES = 0x53, + MIP_CMD_DESC_3DM_LOWPASS_FILTER = 0x54, MIP_CMD_DESC_3DM_DATASTREAM_FORMAT = 0x60, MIP_CMD_DESC_3DM_DEVICE_POWER_STATE = 0x61, MIP_CMD_DESC_3DM_SAVE_RESTORE_GPS_SETTINGS = 0x62, @@ -136,6 +138,7 @@ enum MIP_REPLY_DESC_3DM_ODOMETER_CONFIG = 0xC3, MIP_REPLY_DESC_3DM_SENSOR_RANGE = 0xD2, MIP_REPLY_DESC_3DM_CALIBRATED_RANGES = 0xD3, + MIP_REPLY_DESC_3DM_LOWPASS_FILTER = 0xD4, }; //////////////////////////////////////////////////////////////////////////////// @@ -143,28 +146,29 @@ enum //////////////////////////////////////////////////////////////////////////////// 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 -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_GLL = 2; ///< Geographic Position Lat/Lon -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_GSV = 3; ///< GNSS Satellites in View -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_RMC = 4; ///< Recommended Minimum Specific GNSS Data -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_VTG = 5; ///< Course over Ground -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_HDT = 6; ///< Heading, True -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_ZDA = 7; ///< Time & Date -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_PRKA = 100; ///< Parker proprietary Euler angles -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_PRKR = 101; ///< Parker proprietary Angular Rate/Acceleration +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_MSRA = 129; ///< MicroStrain 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_MSRR = 130; ///< MicroStrain 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_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" +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". struct mip_nmea_message { - mip_nmea_message_message_id message_id; ///< Message type (GGA, GLL, etc) - mip_nmea_message_talker_id talker_id; ///< Talker ID (GN, GP, etc) - uint8_t source_desc_set; ///< Data source descriptor set (Filter, GNSS, etc) - uint16_t decimation; ///< Decimation from the base rate of the source descriptor set. + mip_nmea_message_message_id message_id; ///< NMEA sentence type. + 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; @@ -209,7 +213,7 @@ 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; ///< Descriptor list. + mip_descriptor_rate descriptors[83]; ///< Descriptor list. }; typedef struct mip_3dm_poll_imu_message_command mip_3dm_poll_imu_message_command; @@ -217,6 +221,7 @@ void insert_mip_3dm_poll_imu_message_command(struct mip_serializer* serializer, void extract_mip_3dm_poll_imu_message_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -236,7 +241,7 @@ 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; ///< Descriptor list. + mip_descriptor_rate descriptors[83]; ///< Descriptor list. }; typedef struct mip_3dm_poll_gnss_message_command mip_3dm_poll_gnss_message_command; @@ -244,6 +249,7 @@ void insert_mip_3dm_poll_gnss_message_command(struct mip_serializer* serializer, void extract_mip_3dm_poll_gnss_message_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -263,7 +269,7 @@ 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; ///< Descriptor format list. + mip_descriptor_rate descriptors[83]; ///< Descriptor format list. }; typedef struct mip_3dm_poll_filter_message_command mip_3dm_poll_filter_message_command; @@ -271,6 +277,7 @@ void insert_mip_3dm_poll_filter_message_command(struct mip_serializer* serialize void extract_mip_3dm_poll_filter_message_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -285,7 +292,7 @@ struct mip_3dm_imu_message_format_command { mip_function_selector function; uint8_t num_descriptors; ///< Number of descriptors - mip_descriptor_rate* descriptors; ///< Descriptor format list. + mip_descriptor_rate descriptors[82]; ///< Descriptor format list. }; typedef struct mip_3dm_imu_message_format_command mip_3dm_imu_message_format_command; @@ -295,7 +302,7 @@ void extract_mip_3dm_imu_message_format_command(struct mip_serializer* serialize struct mip_3dm_imu_message_format_response { uint8_t num_descriptors; ///< Number of descriptors - mip_descriptor_rate* descriptors; ///< Descriptor format list. + mip_descriptor_rate descriptors[82]; ///< Descriptor format list. }; typedef struct mip_3dm_imu_message_format_response mip_3dm_imu_message_format_response; @@ -307,6 +314,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -321,7 +329,7 @@ struct mip_3dm_gps_message_format_command { mip_function_selector function; uint8_t num_descriptors; ///< Number of descriptors - mip_descriptor_rate* descriptors; ///< Descriptor format list. + mip_descriptor_rate descriptors[82]; ///< Descriptor format list. }; typedef struct mip_3dm_gps_message_format_command mip_3dm_gps_message_format_command; @@ -331,7 +339,7 @@ void extract_mip_3dm_gps_message_format_command(struct mip_serializer* serialize struct mip_3dm_gps_message_format_response { uint8_t num_descriptors; ///< Number of descriptors - mip_descriptor_rate* descriptors; ///< Descriptor format list. + mip_descriptor_rate descriptors[82]; ///< Descriptor format list. }; typedef struct mip_3dm_gps_message_format_response mip_3dm_gps_message_format_response; @@ -343,6 +351,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -357,7 +366,7 @@ 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; + mip_descriptor_rate descriptors[82]; }; typedef struct mip_3dm_filter_message_format_command mip_3dm_filter_message_format_command; @@ -367,7 +376,7 @@ void extract_mip_3dm_filter_message_format_command(struct mip_serializer* serial struct mip_3dm_filter_message_format_response { uint8_t num_descriptors; ///< Number of descriptors (limited by payload size) - mip_descriptor_rate* descriptors; + mip_descriptor_rate descriptors[82]; }; typedef struct mip_3dm_filter_message_format_response mip_3dm_filter_message_format_response; @@ -379,6 +388,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -400,6 +410,7 @@ void insert_mip_3dm_imu_get_base_rate_response(struct mip_serializer* serializer void extract_mip_3dm_imu_get_base_rate_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -421,6 +432,7 @@ void insert_mip_3dm_gps_get_base_rate_response(struct mip_serializer* serializer void extract_mip_3dm_gps_get_base_rate_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -442,6 +454,7 @@ void insert_mip_3dm_filter_get_base_rate_response(struct mip_serializer* seriali void extract_mip_3dm_filter_get_base_rate_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -462,7 +475,7 @@ struct mip_3dm_poll_data_command uint8_t desc_set; ///< Data descriptor set. Must be supported. bool suppress_ack; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors; ///< Number of descriptors in the format list. - uint8_t* descriptors; ///< Descriptor format list. + uint8_t descriptors[82]; ///< Descriptor format list. }; typedef struct mip_3dm_poll_data_command mip_3dm_poll_data_command; @@ -470,6 +483,7 @@ void insert_mip_3dm_poll_data_command(struct mip_serializer* serializer, const m void extract_mip_3dm_poll_data_command(struct mip_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,6 +512,7 @@ void insert_mip_3dm_get_base_rate_response(struct mip_serializer* serializer, co void extract_mip_3dm_get_base_rate_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -513,7 +528,7 @@ struct mip_3dm_message_format_command mip_function_selector function; 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; ///< List of descriptors and decimations. + mip_descriptor_rate descriptors[82]; ///< List of descriptors and decimations. }; typedef struct mip_3dm_message_format_command mip_3dm_message_format_command; @@ -524,7 +539,7 @@ 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; ///< List of descriptors and decimations. + mip_descriptor_rate descriptors[82]; ///< List of descriptors and decimations. }; typedef struct mip_3dm_message_format_response mip_3dm_message_format_response; @@ -536,6 +551,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -554,7 +570,7 @@ 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; ///< List of format entries. + mip_nmea_message format_entries[40]; ///< List of format entries. }; typedef struct mip_3dm_nmea_poll_data_command mip_3dm_nmea_poll_data_command; @@ -562,6 +578,7 @@ void insert_mip_3dm_nmea_poll_data_command(struct mip_serializer* serializer, co void extract_mip_3dm_nmea_poll_data_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -574,7 +591,7 @@ 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; ///< List of format entries. + mip_nmea_message format_entries[40]; ///< List of format entries. }; typedef struct mip_3dm_nmea_message_format_command mip_3dm_nmea_message_format_command; @@ -584,7 +601,7 @@ void extract_mip_3dm_nmea_message_format_command(struct mip_serializer* serializ struct mip_3dm_nmea_message_format_response { uint8_t count; ///< Number of format entries (limited by payload size) - mip_nmea_message* format_entries; ///< List of format entries. + mip_nmea_message format_entries[40]; ///< List of format entries. }; typedef struct mip_3dm_nmea_message_format_response mip_3dm_nmea_message_format_response; @@ -596,6 +613,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -620,6 +638,7 @@ void extract_mip_3dm_device_settings_command(struct mip_serializer* serializer, 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -666,6 +685,7 @@ 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_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device); mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -696,6 +716,7 @@ void insert_mip_3dm_factory_streaming_command_action(struct mip_serializer* seri void extract_mip_3dm_factory_streaming_command_action(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -739,6 +760,94 @@ 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_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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_3dm_constellation_settings (0x0C,0x21) Constellation Settings [C] +/// 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): +/// 0 to max_channels_available (from reply message) +/// +/// For each constellation you wish to use, include a ConstellationSettings struct. Note the following: +/// +/// Total number of tracking channels (sum of "reserved_channels" for all constellations) must be <= 32: +/// 0 -> 32 Number of reserved channels +/// 0 -> 32 Max number of channels (>= reserved channels) +/// +/// The factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3. +/// +/// Warning: SBAS functionality shall not be used in "safety of life" applications! +/// Warning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK. +/// Warning: You cannot enable GLONASS and BeiDou at the same time. +/// Note: Enabling SBAS and QZSS augments GPS accuracy. +/// Note: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used. +/// +///@{ + +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) + +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; + +struct mip_3dm_constellation_settings_command_settings +{ + mip_3dm_constellation_settings_command_constellation_id constellation_id; ///< Constellation ID + uint8_t enable; ///< Enable/Disable constellation + 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; +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(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_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_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_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); + +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(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); + +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -752,9 +861,10 @@ mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, typedef uint16_t mip_3dm_gnss_sbas_settings_command_sbasoptions; static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_NONE = 0x0000; -static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_ENABLE_RANGING = 0x0001; ///< Use SBAS pseudoranges in position solution +static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_ENABLE_RANGING = 0x0001; ///< Use SBAS pseudo-ranges in position solution 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; struct mip_3dm_gnss_sbas_settings_command { @@ -762,7 +872,7 @@ struct mip_3dm_gnss_sbas_settings_command 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; ///< List of specific SBAS PRNs to search for + 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; @@ -777,7 +887,7 @@ 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; ///< List of specific SBAS PRNs to search for + 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; @@ -789,6 +899,59 @@ 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_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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_3dm_gnss_assisted_fix (0x0C,0x23) Gnss Assisted Fix [C] +/// Set the options for assisted GNSS fix. +/// +/// Devices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM. +/// These 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. +/// The 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. +/// +/// The 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. +/// This allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF. +/// +/// NOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state. +/// WARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles +/// +///@{ + +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 + +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(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_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); + +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(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); + +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -825,12 +988,15 @@ void extract_mip_3dm_gnss_time_assistance_response(struct mip_serializer* serial 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_adv_lowpass_filter (0x0C,0x50) Adv Lowpass Filter [C] +///@defgroup c_3dm_imu_lowpass_filter (0x0C,0x50) Imu Lowpass Filter [C] /// Advanced configuration for the IMU data quantity low-pass filters. /// +/// Deprecated, use the lowpass filter (0x0C,0x54) command instead. +/// /// The scaled data quantities are by default filtered through a single-pole IIR low-pass filter /// which is configured with a -3dB cutoff frequency of half the reporting frequency (set by /// decimation factor in the IMU Message Format command) to prevent aliasing on a per data @@ -839,14 +1005,14 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d /// complete bypass of the digital low-pass filter. /// /// Possible data descriptors: -/// 0x04 – Scaled accelerometer data -/// 0x05 – Scaled gyro data -/// 0x06 – Scaled magnetometer data (if applicable) -/// 0x17 – Scaled pressure data (if applicable) +/// 0x04 - Scaled accelerometer data +/// 0x05 - Scaled gyro data +/// 0x06 - Scaled magnetometer data (if applicable) +/// 0x17 - Scaled pressure data (if applicable) /// ///@{ -struct mip_3dm_adv_lowpass_filter_command +struct mip_3dm_imu_lowpass_filter_command { mip_function_selector function; uint8_t target_descriptor; ///< 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. @@ -856,11 +1022,11 @@ struct mip_3dm_adv_lowpass_filter_command uint8_t reserved; ///< Reserved, set to 0x00. }; -typedef struct mip_3dm_adv_lowpass_filter_command mip_3dm_adv_lowpass_filter_command; -void insert_mip_3dm_adv_lowpass_filter_command(struct mip_serializer* serializer, const mip_3dm_adv_lowpass_filter_command* self); -void extract_mip_3dm_adv_lowpass_filter_command(struct mip_serializer* serializer, mip_3dm_adv_lowpass_filter_command* self); +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); -struct mip_3dm_adv_lowpass_filter_response +struct mip_3dm_imu_lowpass_filter_response { uint8_t target_descriptor; bool enable; ///< True if the filter is currently enabled. @@ -869,15 +1035,16 @@ struct mip_3dm_adv_lowpass_filter_response uint8_t reserved; ///< Reserved and must be ignored. }; -typedef struct mip_3dm_adv_lowpass_filter_response mip_3dm_adv_lowpass_filter_response; -void insert_mip_3dm_adv_lowpass_filter_response(struct mip_serializer* serializer, const mip_3dm_adv_lowpass_filter_response* self); -void extract_mip_3dm_adv_lowpass_filter_response(struct mip_serializer* serializer, mip_3dm_adv_lowpass_filter_response* self); +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); + +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_adv_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_adv_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_adv_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor); -mip_cmd_result mip_3dm_load_adv_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor); -mip_cmd_result mip_3dm_default_adv_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor); ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -920,6 +1087,7 @@ 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_cmd_result mip_3dm_load_pps_source(struct mip_interface* device); mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -950,27 +1118,31 @@ static const mip_3dm_gpio_config_command_feature MIP_3DM_GPIO_CONFIG_COMMAND_FEA 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_POWER = 5; ///< Controls the device power state (e.g. enter low power mode). +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_POWER_SHUTDOWN = 1; ///< A logic 1 applied to the pin will place the device in low-power mode. A full restart is executed after the signal is removed. +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. 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; -static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_OPEN_DRAIN = 0x01; ///< 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 pullup 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. -static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_PULLDOWN = 0x02; ///< The pin will have an internal pulldown 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 pullup. 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 pullup 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 pulldown. 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_OPEN_DRAIN = 0x01; ///< 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. +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; struct mip_3dm_gpio_config_command { @@ -1011,6 +1183,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1029,7 +1202,7 @@ mip_cmd_result mip_3dm_default_gpio_config(struct mip_interface* device, uint8_t /// While the state of a pin can always be set, it will only have an observable effect if /// the pin is set to output mode. /// -/// This command does not support saving, loading, or reseting the state. Instead, use the +/// This command does not support saving, loading, or resetting the state. Instead, use the /// GPIO Configuration command, which allows the initial state to be configured. /// ///@{ @@ -1057,6 +1230,7 @@ void extract_mip_3dm_gpio_state_response(struct mip_serializer* serializer, mip_ 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1101,6 +1275,7 @@ 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_cmd_result mip_3dm_load_odometer(struct mip_interface* device); mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1164,6 +1339,7 @@ void insert_mip_3dm_get_event_support_response(struct mip_serializer* serializer void extract_mip_3dm_get_event_support_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1216,6 +1392,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1228,6 +1405,7 @@ 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_ACTIVE = 0x01; ///< True if the trigger is currently active (either due to its logic or being in test mode). 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; struct mip_3dm_get_event_trigger_status_command_entry { @@ -1263,6 +1441,7 @@ void insert_mip_3dm_get_event_trigger_status_response(struct mip_serializer* ser void extract_mip_3dm_get_event_trigger_status_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1301,6 +1480,7 @@ void insert_mip_3dm_get_event_action_status_response(struct mip_serializer* seri void extract_mip_3dm_get_event_action_status_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1425,6 +1605,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1511,6 +1692,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1524,7 +1706,7 @@ mip_cmd_result mip_3dm_default_event_action(struct mip_interface* device, uint8_ struct mip_3dm_accel_bias_command { mip_function_selector function; - float bias[3]; ///< accelerometer bias in the sensor frame (x,y,z) [g] + 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; @@ -1533,7 +1715,7 @@ void extract_mip_3dm_accel_bias_command(struct mip_serializer* serializer, mip_3 struct mip_3dm_accel_bias_response { - float bias[3]; ///< accelerometer bias in the sensor frame (x,y,z) [g] + 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; @@ -1545,6 +1727,7 @@ 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_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device); mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1558,7 +1741,7 @@ mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device); struct mip_3dm_gyro_bias_command { mip_function_selector function; - float bias[3]; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + 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; @@ -1567,7 +1750,7 @@ void extract_mip_3dm_gyro_bias_command(struct mip_serializer* serializer, mip_3d struct mip_3dm_gyro_bias_response { - float bias[3]; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + 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; @@ -1579,6 +1762,7 @@ 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_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device); mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1603,7 +1787,7 @@ void extract_mip_3dm_capture_gyro_bias_command(struct mip_serializer* serializer struct mip_3dm_capture_gyro_bias_response { - float bias[3]; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + 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; @@ -1611,6 +1795,7 @@ void insert_mip_3dm_capture_gyro_bias_response(struct mip_serializer* serializer void extract_mip_3dm_capture_gyro_bias_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1628,7 +1813,7 @@ mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t struct mip_3dm_mag_hard_iron_offset_command { mip_function_selector function; - float offset[3]; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] + 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; @@ -1637,7 +1822,7 @@ void extract_mip_3dm_mag_hard_iron_offset_command(struct mip_serializer* seriali struct mip_3dm_mag_hard_iron_offset_response { - float offset[3]; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] + 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; @@ -1649,6 +1834,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1670,7 +1856,7 @@ mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device struct mip_3dm_mag_soft_iron_matrix_command { mip_function_selector function; - float offset[9]; ///< soft iron matrix [dimensionless] + mip_matrix3f offset; ///< soft iron matrix [dimensionless] }; typedef struct mip_3dm_mag_soft_iron_matrix_command mip_3dm_mag_soft_iron_matrix_command; @@ -1679,7 +1865,7 @@ void extract_mip_3dm_mag_soft_iron_matrix_command(struct mip_serializer* seriali struct mip_3dm_mag_soft_iron_matrix_response { - float offset[9]; ///< soft iron matrix [dimensionless] + mip_matrix3f offset; ///< soft iron matrix [dimensionless] }; typedef struct mip_3dm_mag_soft_iron_matrix_response mip_3dm_mag_soft_iron_matrix_response; @@ -1691,6 +1877,40 @@ 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_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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_3dm_coning_sculling_enable (0x0C,0x3E) Coning Sculling Enable [C] +/// Controls the Coning and Sculling Compenstation setting. +/// +///@{ + +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(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); + +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(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); + +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1751,6 +1971,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1764,7 +1985,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_inter /// EQSTART p^{veh} = q^{-1} p^{sen} q EQEND
/// /// Where:
-/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion desrcribing the transformation.
+/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
/// EQSTART 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.
/// EQSTART 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.
/// @@ -1794,7 +2015,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_inter struct mip_3dm_sensor_2_vehicle_transform_quaternion_command { mip_function_selector function; - float q[4]; ///< Unit length quaternion representing transform [w, i, j, k] + 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; @@ -1803,7 +2024,7 @@ void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(struct mip_se struct mip_3dm_sensor_2_vehicle_transform_quaternion_response { - float q[4]; ///< Unit length quaternion representing transform [w, i, j, k] + 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; @@ -1815,6 +2036,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1856,7 +2078,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_ struct mip_3dm_sensor_2_vehicle_transform_dcm_command { mip_function_selector function; - float dcm[9]; ///< 3 x 3 direction cosine matrix, stored in row-major order + 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; @@ -1865,7 +2087,7 @@ void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(struct mip_serialize struct mip_3dm_sensor_2_vehicle_transform_dcm_response { - float dcm[9]; ///< 3 x 3 direction cosine matrix, stored in row-major order + 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; @@ -1877,6 +2099,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1884,7 +2107,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interfa /// 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), -/// and to correct for heading using the magnetomer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field). +/// and to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field). /// Pitch/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. /// ///@{ @@ -1919,6 +2142,7 @@ 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_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device); mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1926,7 +2150,7 @@ mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device /// Changes the IMU sensor gain. /// /// This allows you to optimize the range to get the best accuracy and performance -/// while minimizing overrange events. +/// while minimizing over-range events. /// /// Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine /// the appropriate setting value for your application. Using values other than @@ -1960,6 +2184,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -2002,6 +2227,61 @@ void insert_mip_3dm_calibrated_sensor_ranges_response(struct mip_serializer* ser void extract_mip_3dm_calibrated_sensor_ranges_response(struct mip_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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_3dm_lowpass_filter (0x0C,0x54) Lowpass Filter [C] +/// 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. +/// +/// If set to automatic mode, the frequency will track half of the transmission rate +/// of the target descriptor according to the configured message format (0x0C,0x0F). +/// For example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter would +/// be set to 50 Hz. Changing the message format to 200 Hz would automatically adjust the +/// filter to 100 Hz. +/// +/// For WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptor +/// may be 0x00 to set, save, load, or reset the setting for all supported descriptors. The +/// field descriptor must be 0x00 if the descriptor set is 0x00. +/// +/// +///@{ + +struct mip_3dm_lowpass_filter_command +{ + mip_function_selector function; + uint8_t desc_set; ///< Descriptor set of the quantity to be filtered. + uint8_t field_desc; ///< Field descriptor of the quantity to be filtered. + 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(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); + +struct mip_3dm_lowpass_filter_response +{ + uint8_t desc_set; ///< Descriptor set of the quantity to be filtered. + uint8_t field_desc; ///< Field descriptor of the quantity to be filtered. + 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(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); + +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); + ///@} /// diff --git a/src/mip/definitions/commands_3dm.hpp b/src/mip/definitions/commands_3dm.hpp index 9aea6c1fb..5d771bd68 100644 --- a/src/mip/definitions/commands_3dm.hpp +++ b/src/mip/definitions/commands_3dm.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -78,10 +79,11 @@ enum CMD_GPIO_CONFIG = 0x41, CMD_GPIO_STATE = 0x42, CMD_ODOMETER_CONFIG = 0x43, - CMD_ADVANCED_DATA_FILTER = 0x50, + CMD_IMU_LOWPASS_FILTER = 0x50, CMD_LEGACY_COMP_FILTER = 0x51, CMD_SENSOR_RANGE = 0x52, CMD_CALIBRATED_RANGES = 0x53, + CMD_LOWPASS_FILTER = 0x54, CMD_DATASTREAM_FORMAT = 0x60, CMD_DEVICE_POWER_STATE = 0x61, CMD_SAVE_RESTORE_GPS_SETTINGS = 0x62, @@ -135,6 +137,7 @@ enum REPLY_ODOMETER_CONFIG = 0xC3, REPLY_SENSOR_RANGE = 0xD2, REPLY_CALIBRATED_RANGES = 0xD3, + REPLY_LOWPASS_FILTER = 0xD4, }; //////////////////////////////////////////////////////////////////////////////// @@ -145,29 +148,30 @@ struct NmeaMessage { enum class MessageID : uint8_t { - GGA = 1, ///< GPS System Fix Data - GLL = 2, ///< Geographic Position Lat/Lon - GSV = 3, ///< GNSS Satellites in View - RMC = 4, ///< Recommended Minimum Specific GNSS Data - VTG = 5, ///< Course over Ground - HDT = 6, ///< Heading, True - ZDA = 7, ///< Time & Date - PRKA = 100, ///< Parker proprietary Euler angles - PRKR = 101, ///< Parker proprietary Angular Rate/Acceleration + GGA = 1, ///< GPS System Fix Data. Source can be the Filter or GNSS1/2 datasets. + GLL = 2, ///< Geographic Position Lat/Lon. Source can be the Filter or GNSS1/2 datasets. + GSV = 3, ///< GNSS Satellites in View. Source must be either GNSS1 or GNSS2 datasets. The talker ID must be set to IGNORED. + RMC = 4, ///< Recommended Minimum Specific GNSS Data. Source can be the Filter or GNSS1/2 datasets. + 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. }; enum class TalkerID : uint8_t { - GNSS = 1, ///< NMEA message will be produced with talker id "GN" - GPS = 2, ///< NMEA message will be produced with talker id "GP" - GALILEO = 3, ///< NMEA message will be produced with talker id "GA" - GLONASS = 4, ///< NMEA message will be produced with talker id "GL" + IGNORED = 0, ///< Talker ID cannot be changed. + GNSS = 1, ///< NMEA message will be produced with talker id "GN". + GPS = 2, ///< NMEA message will be produced with talker id "GP". + GALILEO = 3, ///< NMEA message will be produced with talker id "GA". + GLONASS = 4, ///< NMEA message will be produced with talker id "GL". }; - MessageID message_id = static_cast(0); ///< Message type (GGA, GLL, etc) - TalkerID talker_id = static_cast(0); ///< Talker ID (GN, GP, etc) - uint8_t source_desc_set = 0; ///< Data source descriptor set (Filter, GNSS, etc) - uint16_t decimation = 0; ///< Decimation from the base rate of the source descriptor set. + 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. }; void insert(Serializer& serializer, const NmeaMessage& self); @@ -202,20 +206,35 @@ enum class SensorRangeType : uint8_t struct PollImuMessage { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_IMU_MESSAGE; - - static const bool HAS_FUNCTION_SELECTOR = false; - bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors = 0; ///< Number of descriptors in the descriptor list. - DescriptorRate* descriptors = {nullptr}; ///< Descriptor list. + DescriptorRate descriptors[83]; ///< Descriptor list. + + 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 + { + return std::make_tuple(suppress_ack,num_descriptors,descriptors); + } + auto as_tuple() + { + return std::make_tuple(std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); + } + typedef void Response; }; void insert(Serializer& serializer, const PollImuMessage& self); void extract(Serializer& serializer, PollImuMessage& self); -CmdResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); +TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -233,20 +252,35 @@ CmdResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t num struct PollGnssMessage { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_GNSS_MESSAGE; - - static const bool HAS_FUNCTION_SELECTOR = false; - bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors = 0; ///< Number of descriptors in the descriptor list. - DescriptorRate* descriptors = {nullptr}; ///< Descriptor list. + DescriptorRate descriptors[83]; ///< Descriptor list. + 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 + { + return std::make_tuple(suppress_ack,num_descriptors,descriptors); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); + } + typedef void Response; }; void insert(Serializer& serializer, const PollGnssMessage& self); void extract(Serializer& serializer, PollGnssMessage& self); -CmdResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); +TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -264,20 +298,35 @@ CmdResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t nu struct PollFilterMessage { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_FILTER_MESSAGE; - - static const bool HAS_FUNCTION_SELECTOR = false; - bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors = 0; ///< Number of descriptors in the format list. - DescriptorRate* descriptors = {nullptr}; ///< Descriptor format list. + DescriptorRate descriptors[83]; ///< Descriptor format list. + + 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 + { + return std::make_tuple(suppress_ack,num_descriptors,descriptors); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); + } + typedef void Response; }; void insert(Serializer& serializer, const PollFilterMessage& self); void extract(Serializer& serializer, PollFilterMessage& self); -CmdResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); +TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -290,27 +339,60 @@ CmdResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t struct ImuMessageFormat { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_IMU_MESSAGE_FORMAT; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t num_descriptors = 0; ///< Number of descriptors - DescriptorRate* descriptors = {nullptr}; ///< Descriptor format list. + DescriptorRate descriptors[82]; ///< Descriptor format list. + + 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 + { + return std::make_tuple(num_descriptors,descriptors); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); + } + + static ImuMessageFormat create_sld_all(::mip::FunctionSelector function) + { + ImuMessageFormat cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_IMU_MESSAGE_FORMAT; - + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; uint8_t num_descriptors = 0; ///< Number of descriptors - DescriptorRate* descriptors = {nullptr}; ///< Descriptor format list. + DescriptorRate descriptors[82]; ///< Descriptor format list. + + auto as_tuple() + { + return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); + } }; }; void insert(Serializer& serializer, const ImuMessageFormat& self); @@ -319,11 +401,12 @@ void extract(Serializer& serializer, ImuMessageFormat& self); void insert(Serializer& serializer, const ImuMessageFormat::Response& self); void extract(Serializer& serializer, ImuMessageFormat::Response& self); -CmdResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); -CmdResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); -CmdResult saveImuMessageFormat(C::mip_interface& device); -CmdResult loadImuMessageFormat(C::mip_interface& device); -CmdResult defaultImuMessageFormat(C::mip_interface& device); +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); +TypedResult loadImuMessageFormat(C::mip_interface& device); +TypedResult defaultImuMessageFormat(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -336,27 +419,60 @@ CmdResult defaultImuMessageFormat(C::mip_interface& device); struct GpsMessageFormat { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_MESSAGE_FORMAT; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t num_descriptors = 0; ///< Number of descriptors - DescriptorRate* descriptors = {nullptr}; ///< Descriptor format list. + DescriptorRate descriptors[82]; ///< Descriptor format list. + + 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 + { + return std::make_tuple(num_descriptors,descriptors); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); + } + + static GpsMessageFormat create_sld_all(::mip::FunctionSelector function) + { + GpsMessageFormat cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_MESSAGE_FORMAT; - + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; uint8_t num_descriptors = 0; ///< Number of descriptors - DescriptorRate* descriptors = {nullptr}; ///< Descriptor format list. + DescriptorRate descriptors[82]; ///< Descriptor format list. + + auto as_tuple() + { + return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); + } }; }; void insert(Serializer& serializer, const GpsMessageFormat& self); @@ -365,11 +481,12 @@ void extract(Serializer& serializer, GpsMessageFormat& self); void insert(Serializer& serializer, const GpsMessageFormat::Response& self); void extract(Serializer& serializer, GpsMessageFormat::Response& self); -CmdResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); -CmdResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); -CmdResult saveGpsMessageFormat(C::mip_interface& device); -CmdResult loadGpsMessageFormat(C::mip_interface& device); -CmdResult defaultGpsMessageFormat(C::mip_interface& device); +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); +TypedResult loadGpsMessageFormat(C::mip_interface& device); +TypedResult defaultGpsMessageFormat(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -382,27 +499,60 @@ CmdResult defaultGpsMessageFormat(C::mip_interface& device); struct FilterMessageFormat { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_FILTER_MESSAGE_FORMAT; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t num_descriptors = 0; ///< Number of descriptors (limited by payload size) - DescriptorRate* descriptors = {nullptr}; + DescriptorRate descriptors[82]; + + 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 + { + return std::make_tuple(num_descriptors,descriptors); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); + } + + static FilterMessageFormat create_sld_all(::mip::FunctionSelector function) + { + FilterMessageFormat cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_FILTER_MESSAGE_FORMAT; - + 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 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 = {nullptr}; + DescriptorRate descriptors[82]; + + auto as_tuple() + { + return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); + } }; }; void insert(Serializer& serializer, const FilterMessageFormat& self); @@ -411,11 +561,12 @@ void extract(Serializer& serializer, FilterMessageFormat& self); void insert(Serializer& serializer, const FilterMessageFormat::Response& self); void extract(Serializer& serializer, FilterMessageFormat::Response& self); -CmdResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); -CmdResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); -CmdResult saveFilterMessageFormat(C::mip_interface& device); -CmdResult loadFilterMessageFormat(C::mip_interface& device); -CmdResult defaultFilterMessageFormat(C::mip_interface& device); +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); +TypedResult loadFilterMessageFormat(C::mip_interface& device); +TypedResult defaultFilterMessageFormat(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -429,19 +580,43 @@ CmdResult defaultFilterMessageFormat(C::mip_interface& device); struct ImuGetBaseRate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_IMU_BASE_RATE; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_IMU_BASE_RATE; - + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint16_t rate = 0; ///< [hz] + + auto as_tuple() + { + return std::make_tuple(std::ref(rate)); + } }; }; void insert(Serializer& serializer, const ImuGetBaseRate& self); @@ -450,7 +625,8 @@ void extract(Serializer& serializer, ImuGetBaseRate& self); void insert(Serializer& serializer, const ImuGetBaseRate::Response& self); void extract(Serializer& serializer, ImuGetBaseRate::Response& self); -CmdResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut); +TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -464,19 +640,43 @@ CmdResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut); struct GpsGetBaseRate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_GNSS_BASE_RATE; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_BASE_RATE; - + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint16_t rate = 0; ///< [hz] + + auto as_tuple() + { + return std::make_tuple(std::ref(rate)); + } }; }; void insert(Serializer& serializer, const GpsGetBaseRate& self); @@ -485,7 +685,8 @@ void extract(Serializer& serializer, GpsGetBaseRate& self); void insert(Serializer& serializer, const GpsGetBaseRate::Response& self); void extract(Serializer& serializer, GpsGetBaseRate::Response& self); -CmdResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut); +TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -499,19 +700,43 @@ CmdResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut); struct FilterGetBaseRate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_FILTER_BASE_RATE; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_FILTER_BASE_RATE; - + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint16_t rate = 0; ///< [hz] + + auto as_tuple() + { + return std::make_tuple(std::ref(rate)); + } }; }; void insert(Serializer& serializer, const FilterGetBaseRate& self); @@ -520,7 +745,8 @@ void extract(Serializer& serializer, FilterGetBaseRate& self); void insert(Serializer& serializer, const FilterGetBaseRate::Response& self); void extract(Serializer& serializer, FilterGetBaseRate::Response& self); -CmdResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut); +TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -538,21 +764,36 @@ CmdResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut); struct PollData { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_DATA; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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 = {nullptr}; ///< Descriptor format list. + uint8_t descriptors[82] = {0}; ///< Descriptor format list. + 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 + { + return std::make_tuple(desc_set,suppress_ack,num_descriptors,descriptors); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); + } + typedef void Response; }; void insert(Serializer& serializer, const PollData& self); void extract(Serializer& serializer, PollData& self); -CmdResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors); +TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -563,21 +804,45 @@ CmdResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, struct GetBaseRate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_BASE_RATE; + uint8_t desc_set = 0; ///< This is the data descriptor set. It must be a supported descriptor. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint8_t desc_set = 0; ///< This is the data descriptor set. It must be a supported descriptor. + 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 + { + return std::make_tuple(desc_set); + } + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set)); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_BASE_RATE; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(rate)); + } }; }; void insert(Serializer& serializer, const GetBaseRate& self); @@ -586,7 +851,8 @@ void extract(Serializer& serializer, GetBaseRate& self); void insert(Serializer& serializer, const GetBaseRate::Response& self); void extract(Serializer& serializer, GetBaseRate::Response& self); -CmdResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut); +TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -599,29 +865,63 @@ CmdResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateO struct MessageFormat { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_MESSAGE_FORMAT; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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 = {nullptr}; ///< List of descriptors and decimations. + DescriptorRate descriptors[82]; ///< List of descriptors and decimations. + + 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 + { + return std::make_tuple(desc_set,num_descriptors,descriptors); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(num_descriptors),std::ref(descriptors)); + } + + static MessageFormat create_sld_all(::mip::FunctionSelector function) + { + MessageFormat cmd; + cmd.function = function; + cmd.desc_set = 0; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_MESSAGE_FORMAT; - + 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 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 = {nullptr}; ///< List of descriptors and decimations. + DescriptorRate descriptors[82]; ///< List of descriptors and decimations. + + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(num_descriptors),std::ref(descriptors)); + } }; }; void insert(Serializer& serializer, const MessageFormat& self); @@ -630,11 +930,12 @@ void extract(Serializer& serializer, MessageFormat& self); void insert(Serializer& serializer, const MessageFormat::Response& self); void extract(Serializer& serializer, MessageFormat::Response& self); -CmdResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors); -CmdResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); -CmdResult saveMessageFormat(C::mip_interface& device, uint8_t descSet); -CmdResult loadMessageFormat(C::mip_interface& device, uint8_t descSet); -CmdResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet); +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); +TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet); +TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -651,20 +952,35 @@ CmdResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet); struct NmeaPollData { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_NMEA_MESSAGE; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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 = {nullptr}; ///< List of format entries. + NmeaMessage format_entries[40]; ///< List of format entries. + + 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 + { + return std::make_tuple(suppress_ack,count,format_entries); + } + auto as_tuple() + { + return std::make_tuple(std::ref(suppress_ack),std::ref(count),std::ref(format_entries)); + } + typedef void Response; }; void insert(Serializer& serializer, const NmeaPollData& self); void extract(Serializer& serializer, NmeaPollData& self); -CmdResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries); +TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -675,27 +991,60 @@ CmdResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count struct NmeaMessageFormat { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_NMEA_MESSAGE_FORMAT; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t count = 0; ///< Number of format entries (limited by payload size) - NmeaMessage* format_entries = {nullptr}; ///< List of format entries. + NmeaMessage format_entries[40]; ///< List of format entries. + + 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 + { + return std::make_tuple(count,format_entries); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(count),std::ref(format_entries)); + } + + static NmeaMessageFormat create_sld_all(::mip::FunctionSelector function) + { + NmeaMessageFormat cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_NMEA_MESSAGE_FORMAT; - + 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 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 = {nullptr}; ///< List of format entries. + NmeaMessage format_entries[40]; ///< List of format entries. + + auto as_tuple() + { + return std::make_tuple(std::ref(count),std::ref(format_entries)); + } }; }; void insert(Serializer& serializer, const NmeaMessageFormat& self); @@ -704,11 +1053,12 @@ void extract(Serializer& serializer, NmeaMessageFormat& self); void insert(Serializer& serializer, const NmeaMessageFormat::Response& self); void extract(Serializer& serializer, NmeaMessageFormat::Response& self); -CmdResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries); -CmdResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut); -CmdResult saveNmeaMessageFormat(C::mip_interface& device); -CmdResult loadNmeaMessageFormat(C::mip_interface& device); -CmdResult defaultNmeaMessageFormat(C::mip_interface& device); +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); +TypedResult loadNmeaMessageFormat(C::mip_interface& device); +TypedResult defaultNmeaMessageFormat(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -723,24 +1073,48 @@ CmdResult defaultNmeaMessageFormat(C::mip_interface& device); struct DeviceSettings { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_DEVICE_STARTUP_SETTINGS; + FunctionSelector function = static_cast(0); - static const bool HAS_WRITE_FUNCTION = false; - static const bool HAS_READ_FUNCTION = false; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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 + { + return std::make_tuple(); + } - FunctionSelector function = static_cast(0); + auto as_tuple() + { + return std::make_tuple(); + } + + static DeviceSettings create_sld_all(::mip::FunctionSelector function) + { + DeviceSettings cmd; + cmd.function = function; + return cmd; + } + typedef void Response; }; void insert(Serializer& serializer, const DeviceSettings& self); void extract(Serializer& serializer, DeviceSettings& self); -CmdResult saveDeviceSettings(C::mip_interface& device); -CmdResult loadDeviceSettings(C::mip_interface& device); -CmdResult defaultDeviceSettings(C::mip_interface& device); +TypedResult saveDeviceSettings(C::mip_interface& device); +TypedResult loadDeviceSettings(C::mip_interface& device); +TypedResult defaultDeviceSettings(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -765,25 +1139,58 @@ CmdResult defaultDeviceSettings(C::mip_interface& device); struct UartBaudrate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_UART_BAUDRATE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint32_t baud = 0; + 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 + { + return std::make_tuple(baud); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(baud)); + } + + static UartBaudrate create_sld_all(::mip::FunctionSelector function) + { + UartBaudrate cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_UART_BAUDRATE; - + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint32_t baud = 0; + + auto as_tuple() + { + return std::make_tuple(std::ref(baud)); + } }; }; void insert(Serializer& serializer, const UartBaudrate& self); @@ -792,11 +1199,12 @@ void extract(Serializer& serializer, UartBaudrate& self); void insert(Serializer& serializer, const UartBaudrate::Response& self); void extract(Serializer& serializer, UartBaudrate::Response& self); -CmdResult writeUartBaudrate(C::mip_interface& device, uint32_t baud); -CmdResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut); -CmdResult saveUartBaudrate(C::mip_interface& device); -CmdResult loadUartBaudrate(C::mip_interface& device); -CmdResult defaultUartBaudrate(C::mip_interface& device); +TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud); +TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut); +TypedResult saveUartBaudrate(C::mip_interface& device); +TypedResult loadUartBaudrate(C::mip_interface& device); +TypedResult defaultUartBaudrate(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -810,11 +1218,6 @@ CmdResult defaultUartBaudrate(C::mip_interface& device); struct FactoryStreaming { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CONFIGURE_FACTORY_STREAMING; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class Action : uint8_t { OVERWRITE = 0, ///< Replaces the message format(s), removing any existing descriptors. @@ -825,11 +1228,31 @@ struct FactoryStreaming Action action = static_cast(0); uint8_t reserved = 0; ///< Reserved. Set to 0x00. + 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 + { + return std::make_tuple(action,reserved); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(action),std::ref(reserved)); + } + typedef void Response; }; void insert(Serializer& serializer, const FactoryStreaming& self); void extract(Serializer& serializer, FactoryStreaming& self); -CmdResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved); +TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -845,31 +1268,65 @@ CmdResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action ac struct DatastreamControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CONTROL_DATA_STREAM; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - - static const uint8_t LEGACY_IMU_STREAM = 0x01; - static const uint8_t LEGACY_GNSS_STREAM = 0x02; - static const uint8_t LEGACY_FILTER_STREAM = 0x03; - static const uint8_t ALL_STREAMS = 0x00; + static constexpr const uint8_t LEGACY_IMU_STREAM = 0x01; + 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; 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. + 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 + { + return std::make_tuple(desc_set,enable); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(enable)); + } + + static DatastreamControl create_sld_all(::mip::FunctionSelector function) + { + DatastreamControl cmd; + cmd.function = function; + cmd.desc_set = 0; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_DATASTREAM_ENABLE; - + 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 uint32_t ECHOED_PARAMS = 0x0001; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t desc_set = 0; bool enabled = 0; + + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(enabled)); + } }; }; void insert(Serializer& serializer, const DatastreamControl& self); @@ -878,11 +1335,157 @@ void extract(Serializer& serializer, DatastreamControl& self); void insert(Serializer& serializer, const DatastreamControl::Response& self); void extract(Serializer& serializer, DatastreamControl::Response& self); -CmdResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable); -CmdResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut); -CmdResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet); -CmdResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet); -CmdResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet); +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); +TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet); +TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_3dm_constellation_settings (0x0C,0x21) Constellation Settings [CPP] +/// 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): +/// 0 to max_channels_available (from reply message) +/// +/// For each constellation you wish to use, include a ConstellationSettings struct. Note the following: +/// +/// Total number of tracking channels (sum of "reserved_channels" for all constellations) must be <= 32: +/// 0 -> 32 Number of reserved channels +/// 0 -> 32 Max number of channels (>= reserved channels) +/// +/// The factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3. +/// +/// Warning: SBAS functionality shall not be used in "safety of life" applications! +/// Warning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK. +/// Warning: You cannot enable GLONASS and BeiDou at the same time. +/// Note: Enabling SBAS and QZSS augments GPS accuracy. +/// Note: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used. +/// +///@{ + +struct ConstellationSettings +{ + enum class ConstellationId : uint8_t + { + GPS = 0, ///< GPS (G1-G32) + SBAS = 1, ///< SBAS (S120-S158) + GALILEO = 2, ///< GALILEO (E1-E36) + BEIDOU = 3, ///< BeiDou (B1-B37) + QZSS = 5, ///< QZSS (Q1-Q5) + GLONASS = 6, ///< GLONASS (R1-R32) + }; + + struct OptionFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + L1SAIF = 0x0001, ///< Available only for QZSS + ALL = 0x0001, + }; + uint16_t value = NONE; + + OptionFlags() : value(NONE) {} + OptionFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + OptionFlags& operator=(uint16_t val) { value = val; return *this; } + OptionFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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 + { + 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 + + }; + FunctionSelector function = static_cast(0); + uint16_t max_channels = 0; + uint8_t config_count = 0; + Settings settings[42]; + + 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 + { + return std::make_tuple(max_channels,config_count,settings); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(max_channels),std::ref(config_count),std::ref(settings)); + } + + static ConstellationSettings create_sld_all(::mip::FunctionSelector function) + { + ConstellationSettings cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(max_channels_available),std::ref(max_channels_use),std::ref(config_count),std::ref(settings)); + } + }; +}; +void insert(Serializer& serializer, const ConstellationSettings& self); +void extract(Serializer& serializer, ConstellationSettings& self); + +void insert(Serializer& serializer, const ConstellationSettings::Settings& self); +void extract(Serializer& serializer, ConstellationSettings::Settings& self); + +void insert(Serializer& serializer, const ConstellationSettings::Response& self); +void extract(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); +TypedResult loadConstellationSettings(C::mip_interface& device); +TypedResult defaultConstellationSettings(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -896,23 +1499,15 @@ CmdResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet); struct GnssSbasSettings { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_SBAS_SETTINGS; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - struct SBASOptions : Bitfield { enum _enumType : uint16_t { NONE = 0x0000, - ENABLE_RANGING = 0x0001, ///< Use SBAS pseudoranges in position solution + ENABLE_RANGING = 0x0001, ///< Use SBAS pseudo-ranges in position solution ENABLE_CORRECTIONS = 0x0002, ///< Use SBAS differential corrections APPLY_INTEGRITY = 0x0004, ///< Use SBAS integrity information. If enabled, only GPS satellites for which integrity information is available will be used. + ALL = 0x0007, }; uint16_t value = NONE; @@ -920,27 +1515,79 @@ struct GnssSbasSettings SBASOptions(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } SBASOptions& operator=(uint16_t val) { value = val; return *this; } - SBASOptions& operator=(int val) { value = val; return *this; } + SBASOptions& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; 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 = {nullptr}; ///< List of specific SBAS PRNs to search for + uint16_t included_prns[39] = {0}; ///< List of specific SBAS PRNs to search for + + 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 + { + return std::make_tuple(enable_sbas,sbas_options,num_included_prns,included_prns); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable_sbas),std::ref(sbas_options),std::ref(num_included_prns),std::ref(included_prns)); + } + + static GnssSbasSettings create_sld_all(::mip::FunctionSelector function) + { + GnssSbasSettings cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_SBAS_SETTINGS; - + 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 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 = {nullptr}; ///< List of specific SBAS PRNs to search for + uint16_t included_prns[39] = {0}; ///< List of specific SBAS PRNs to search for + + auto as_tuple() + { + return std::make_tuple(std::ref(enable_sbas),std::ref(sbas_options),std::ref(num_included_prns),std::ref(included_prns)); + } }; }; void insert(Serializer& serializer, const GnssSbasSettings& self); @@ -949,11 +1596,106 @@ void extract(Serializer& serializer, GnssSbasSettings& self); void insert(Serializer& serializer, const GnssSbasSettings::Response& self); void extract(Serializer& serializer, GnssSbasSettings::Response& self); -CmdResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns); -CmdResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut); -CmdResult saveGnssSbasSettings(C::mip_interface& device); -CmdResult loadGnssSbasSettings(C::mip_interface& device); -CmdResult defaultGnssSbasSettings(C::mip_interface& device); +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); +TypedResult loadGnssSbasSettings(C::mip_interface& device); +TypedResult defaultGnssSbasSettings(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_3dm_gnss_assisted_fix (0x0C,0x23) Gnss Assisted Fix [CPP] +/// Set the options for assisted GNSS fix. +/// +/// Devices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM. +/// These 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. +/// The 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. +/// +/// The 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. +/// This allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF. +/// +/// NOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state. +/// WARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles +/// +///@{ + +struct GnssAssistedFix +{ + enum class AssistedFixOption : uint8_t + { + NONE = 0, ///< No assisted fix (default) + ENABLED = 1, ///< Enable assisted fix + }; + + FunctionSelector function = static_cast(0); + AssistedFixOption option = static_cast(0); ///< Assisted fix options + uint8_t flags = 0; ///< Assisted fix flags (set to 0xFF) + + 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 + { + return std::make_tuple(option,flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(option),std::ref(flags)); + } + + static GnssAssistedFix create_sld_all(::mip::FunctionSelector function) + { + GnssAssistedFix cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(option),std::ref(flags)); + } + }; +}; +void insert(Serializer& serializer, const GnssAssistedFix& self); +void extract(Serializer& serializer, GnssAssistedFix& self); + +void insert(Serializer& serializer, const GnssAssistedFix::Response& self); +void extract(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); +TypedResult loadGnssAssistedFix(C::mip_interface& device); +TypedResult defaultGnssAssistedFix(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -967,29 +1709,62 @@ CmdResult defaultGnssSbasSettings(C::mip_interface& device); struct GnssTimeAssistance { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_TIME_ASSISTANCE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = false; - static const bool HAS_LOAD_FUNCTION = false; - static const bool HAS_RESET_FUNCTION = false; - 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] + 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 + { + return std::make_tuple(tow,week_number,accuracy); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(accuracy)); + } + + static GnssTimeAssistance create_sld_all(::mip::FunctionSelector function) + { + GnssTimeAssistance cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_TIME_ASSISTANCE; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(accuracy)); + } }; }; void insert(Serializer& serializer, const GnssTimeAssistance& self); @@ -998,14 +1773,17 @@ void extract(Serializer& serializer, GnssTimeAssistance& self); void insert(Serializer& serializer, const GnssTimeAssistance::Response& self); void extract(Serializer& serializer, GnssTimeAssistance::Response& self); -CmdResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy); -CmdResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut); +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_adv_lowpass_filter (0x0C,0x50) Adv Lowpass Filter [CPP] +///@defgroup cpp_3dm_imu_lowpass_filter (0x0C,0x50) Imu Lowpass Filter [CPP] /// Advanced configuration for the IMU data quantity low-pass filters. /// +/// Deprecated, use the lowpass filter (0x0C,0x54) command instead. +/// /// The scaled data quantities are by default filtered through a single-pole IIR low-pass filter /// which is configured with a -3dB cutoff frequency of half the reporting frequency (set by /// decimation factor in the IMU Message Format command) to prevent aliasing on a per data @@ -1014,24 +1792,15 @@ CmdResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint1 /// complete bypass of the digital low-pass filter. /// /// Possible data descriptors: -/// 0x04 – Scaled accelerometer data -/// 0x05 – Scaled gyro data -/// 0x06 – Scaled magnetometer data (if applicable) -/// 0x17 – Scaled pressure data (if applicable) +/// 0x04 - Scaled accelerometer data +/// 0x05 - Scaled gyro data +/// 0x06 - Scaled magnetometer data (if applicable) +/// 0x17 - Scaled pressure data (if applicable) /// ///@{ -struct AdvLowpassFilter +struct ImuLowpassFilter { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_ADVANCED_DATA_FILTER; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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. @@ -1039,30 +1808,74 @@ struct AdvLowpassFilter 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. + 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 + { + return std::make_tuple(target_descriptor,enable,manual,frequency,reserved); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(target_descriptor),std::ref(enable),std::ref(manual),std::ref(frequency),std::ref(reserved)); + } + + static ImuLowpassFilter create_sld_all(::mip::FunctionSelector function) + { + ImuLowpassFilter cmd; + cmd.function = function; + cmd.target_descriptor = 0; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_ADVANCED_DATA_FILTER; - + 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; 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. + + auto as_tuple() + { + return std::make_tuple(std::ref(target_descriptor),std::ref(enable),std::ref(manual),std::ref(frequency),std::ref(reserved)); + } }; }; -void insert(Serializer& serializer, const AdvLowpassFilter& self); -void extract(Serializer& serializer, AdvLowpassFilter& self); +void insert(Serializer& serializer, const ImuLowpassFilter& self); +void extract(Serializer& serializer, ImuLowpassFilter& self); -void insert(Serializer& serializer, const AdvLowpassFilter::Response& self); -void extract(Serializer& serializer, AdvLowpassFilter::Response& self); +void insert(Serializer& serializer, const ImuLowpassFilter::Response& self); +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); +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); +TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor); +TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor); -CmdResult writeAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved); -CmdResult readAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut); -CmdResult saveAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor); -CmdResult loadAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor); -CmdResult defaultAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor); ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1073,15 +1886,6 @@ CmdResult defaultAdvLowpassFilter(C::mip_interface& device, uint8_t targetDescri struct PpsSource { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_PPS_SOURCE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class Source : uint8_t { DISABLED = 0, ///< PPS output is disabled. Not valid for PPS source command. @@ -1094,13 +1898,55 @@ struct PpsSource FunctionSelector function = static_cast(0); Source source = static_cast(0); + 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 + { + return std::make_tuple(source); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } + + static PpsSource create_sld_all(::mip::FunctionSelector function) + { + PpsSource cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_PPS_SOURCE; - + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; Source source = static_cast(0); + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } }; }; void insert(Serializer& serializer, const PpsSource& self); @@ -1109,11 +1955,12 @@ void extract(Serializer& serializer, PpsSource& self); void insert(Serializer& serializer, const PpsSource::Response& self); void extract(Serializer& serializer, PpsSource::Response& self); -CmdResult writePpsSource(C::mip_interface& device, PpsSource::Source source); -CmdResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut); -CmdResult savePpsSource(C::mip_interface& device); -CmdResult loadPpsSource(C::mip_interface& device); -CmdResult defaultPpsSource(C::mip_interface& device); +TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source); +TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut); +TypedResult savePpsSource(C::mip_interface& device); +TypedResult loadPpsSource(C::mip_interface& device); +TypedResult defaultPpsSource(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1140,15 +1987,6 @@ CmdResult defaultPpsSource(C::mip_interface& device); struct GpioConfig { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GPIO_CONFIG; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class Feature : uint8_t { 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. @@ -1156,7 +1994,7 @@ struct GpioConfig PPS = 2, ///< Pulse per second input or output. ENCODER = 3, ///< Motor encoder/odometer input. TIMESTAMP = 4, ///< Precision Timestamping. Use with Event Trigger Configuration (0x0C,0x2E). - POWER = 5, ///< Controls the device power state (e.g. enter low power mode). + UART = 5, ///< UART data or control lines. }; enum class Behavior : uint8_t @@ -1172,7 +2010,10 @@ struct GpioConfig TIMESTAMP_RISING = 1, ///< Rising edges will be timestamped. TIMESTAMP_FALLING = 2, ///< Falling edges will be timestamped. TIMESTAMP_EITHER = 3, ///< Both rising and falling edges will be timestamped. - POWER_SHUTDOWN = 1, ///< A logic 1 applied to the pin will place the device in low-power mode. A full restart is executed after the signal is removed. + UART_PORT2_TX = 33, ///< (0x21) UART port 2 transmit. + UART_PORT2_RX = 34, ///< (0x22) UART port 2 receive. + UART_PORT3_TX = 49, ///< (0x31) UART port 3 transmit. + UART_PORT3_RX = 50, ///< (0x32) UART port 3 receive. }; struct PinMode : Bitfield @@ -1180,9 +2021,10 @@ struct GpioConfig enum _enumType : uint8_t { NONE = 0x00, - OPEN_DRAIN = 0x01, ///< 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 pullup 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. - PULLDOWN = 0x02, ///< The pin will have an internal pulldown 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 pullup. See the device specifications for the resistance value. - PULLUP = 0x04, ///< The pin will have an internal pullup 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 pulldown. 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. + OPEN_DRAIN = 0x01, ///< 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. + 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. + 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. + ALL = 0x07, }; uint8_t value = NONE; @@ -1190,9 +2032,19 @@ struct GpioConfig PinMode(int val) : value((uint8_t)val) {} operator uint8_t() const { return value; } PinMode& operator=(uint8_t val) { value = val; return *this; } - PinMode& operator=(int val) { value = val; return *this; } + PinMode& operator=(int val) { value = uint8_t(val); return *this; } 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; } }; FunctionSelector function = static_cast(0); @@ -1201,16 +2053,59 @@ struct GpioConfig 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. + 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 + { + return std::make_tuple(pin,feature,behavior,pin_mode); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(pin),std::ref(feature),std::ref(behavior),std::ref(pin_mode)); + } + + static GpioConfig create_sld_all(::mip::FunctionSelector function) + { + GpioConfig cmd; + cmd.function = function; + cmd.pin = 0; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GPIO_CONFIG; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(pin),std::ref(feature),std::ref(behavior),std::ref(pin_mode)); + } }; }; void insert(Serializer& serializer, const GpioConfig& self); @@ -1219,11 +2114,12 @@ void extract(Serializer& serializer, GpioConfig& self); void insert(Serializer& serializer, const GpioConfig::Response& self); void extract(Serializer& serializer, GpioConfig::Response& self); -CmdResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode); -CmdResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut); -CmdResult saveGpioConfig(C::mip_interface& device, uint8_t pin); -CmdResult loadGpioConfig(C::mip_interface& device, uint8_t pin); -CmdResult defaultGpioConfig(C::mip_interface& device, uint8_t pin); +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); +TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin); +TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1242,34 +2138,67 @@ CmdResult defaultGpioConfig(C::mip_interface& device, uint8_t pin); /// While the state of a pin can always be set, it will only have an observable effect if /// the pin is set to output mode. /// -/// This command does not support saving, loading, or reseting the state. Instead, use the +/// This command does not support saving, loading, or resetting the state. Instead, use the /// GPIO Configuration command, which allows the initial state to be configured. /// ///@{ struct GpioState { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GPIO_STATE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = false; - static const bool HAS_LOAD_FUNCTION = false; - static const bool HAS_RESET_FUNCTION = false; - FunctionSelector function = static_cast(0); uint8_t pin = 0; ///< GPIO pin number counting from 1. Cannot be 0. bool state = 0; ///< The pin state. + 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 + { + return std::make_tuple(pin,state); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(pin),std::ref(state)); + } + + static GpioState create_sld_all(::mip::FunctionSelector function) + { + GpioState cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GPIO_STATE; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(pin),std::ref(state)); + } }; }; void insert(Serializer& serializer, const GpioState& self); @@ -1278,8 +2207,9 @@ void extract(Serializer& serializer, GpioState& self); void insert(Serializer& serializer, const GpioState::Response& self); void extract(Serializer& serializer, GpioState::Response& self); -CmdResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state); -CmdResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut); +TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state); +TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1291,15 +2221,6 @@ CmdResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut); struct Odometer { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_ODOMETER_CONFIG; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class Mode : uint8_t { DISABLED = 0, ///< Encoder is disabled. @@ -1311,15 +2232,57 @@ struct Odometer 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]. + 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 + { + return std::make_tuple(mode,scaling,uncertainty); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(mode),std::ref(scaling),std::ref(uncertainty)); + } + + static Odometer create_sld_all(::mip::FunctionSelector function) + { + Odometer cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_ODOMETER_CONFIG; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(mode),std::ref(scaling),std::ref(uncertainty)); + } }; }; void insert(Serializer& serializer, const Odometer& self); @@ -1328,11 +2291,12 @@ void extract(Serializer& serializer, Odometer& self); void insert(Serializer& serializer, const Odometer::Response& self); void extract(Serializer& serializer, Odometer::Response& self); -CmdResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty); -CmdResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut); -CmdResult saveOdometer(C::mip_interface& device); -CmdResult loadOdometer(C::mip_interface& device); -CmdResult defaultOdometer(C::mip_interface& device); +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); +TypedResult loadOdometer(C::mip_interface& device); +TypedResult defaultOdometer(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1359,11 +2323,6 @@ CmdResult defaultOdometer(C::mip_interface& device); struct GetEventSupport { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_SUPPORT; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class Query : uint8_t { TRIGGER_TYPES = 1, ///< Query the supported trigger types and max count for each. @@ -1378,16 +2337,45 @@ struct GetEventSupport }; Query query = static_cast(0); ///< What type of information to retrieve. + 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 + { + return std::make_tuple(query); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(query)); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_SUPPORT; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(query),std::ref(max_instances),std::ref(num_entries),std::ref(entries)); + } }; }; void insert(Serializer& serializer, const GetEventSupport& self); @@ -1399,7 +2387,8 @@ void extract(Serializer& serializer, GetEventSupport::Info& self); void insert(Serializer& serializer, const GetEventSupport::Response& self); void extract(Serializer& serializer, GetEventSupport::Response& self); -CmdResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut); +TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1419,15 +2408,6 @@ CmdResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query struct EventControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_CONTROL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class Mode : uint8_t { DISABLED = 0, ///< Trigger is disabled. @@ -1440,14 +2420,57 @@ struct EventControl 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. + 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 + { + return std::make_tuple(instance,mode); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(instance),std::ref(mode)); + } + + static EventControl create_sld_all(::mip::FunctionSelector function) + { + EventControl cmd; + cmd.function = function; + cmd.instance = 0; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_CONTROL; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(instance),std::ref(mode)); + } }; }; void insert(Serializer& serializer, const EventControl& self); @@ -1456,11 +2479,12 @@ void extract(Serializer& serializer, EventControl& self); void insert(Serializer& serializer, const EventControl::Response& self); void extract(Serializer& serializer, EventControl::Response& self); -CmdResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode); -CmdResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut); -CmdResult saveEventControl(C::mip_interface& device, uint8_t instance); -CmdResult loadEventControl(C::mip_interface& device, uint8_t instance); -CmdResult defaultEventControl(C::mip_interface& device, uint8_t instance); +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); +TypedResult loadEventControl(C::mip_interface& device, uint8_t instance); +TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1470,11 +2494,6 @@ CmdResult defaultEventControl(C::mip_interface& device, uint8_t instance); struct GetEventTriggerStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_TRIGGER_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct Status : Bitfield { enum _enumType : uint8_t @@ -1483,6 +2502,7 @@ struct GetEventTriggerStatus ACTIVE = 0x01, ///< True if the trigger is currently active (either due to its logic or being in test mode). ENABLED = 0x02, ///< True if the trigger is enabled. TEST = 0x04, ///< True if the trigger is in test mode. + ALL = 0x07, }; uint8_t value = NONE; @@ -1490,9 +2510,19 @@ struct GetEventTriggerStatus Status(int val) : value((uint8_t)val) {} operator uint8_t() const { return value; } Status& operator=(uint8_t val) { value = val; return *this; } - Status& operator=(int val) { value = val; return *this; } + Status& operator=(int val) { value = uint8_t(val); return *this; } 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 @@ -1504,14 +2534,43 @@ struct GetEventTriggerStatus 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. + 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 + { + return std::make_tuple(requested_count,requested_instances); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(requested_count),std::ref(requested_instances)); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_TRIGGER_STATUS; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(count),std::ref(triggers)); + } }; }; void insert(Serializer& serializer, const GetEventTriggerStatus& self); @@ -1523,7 +2582,8 @@ void extract(Serializer& serializer, GetEventTriggerStatus::Entry& self); void insert(Serializer& serializer, const GetEventTriggerStatus::Response& self); void extract(Serializer& serializer, GetEventTriggerStatus::Response& self); -CmdResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut); +TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1533,11 +2593,6 @@ CmdResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount struct GetEventActionStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_ACTION_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct Entry { uint8_t action_type = 0; ///< Configured action type. @@ -1547,14 +2602,43 @@ struct GetEventActionStatus 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. + 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 + { + return std::make_tuple(requested_count,requested_instances); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(requested_count),std::ref(requested_instances)); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_ACTION_STATUS; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(count),std::ref(actions)); + } }; }; void insert(Serializer& serializer, const GetEventActionStatus& self); @@ -1566,7 +2650,8 @@ void extract(Serializer& serializer, GetEventActionStatus::Entry& self); void insert(Serializer& serializer, const GetEventActionStatus::Response& self); void extract(Serializer& serializer, GetEventActionStatus::Response& self); -CmdResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut); +TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1577,15 +2662,6 @@ CmdResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, struct EventTrigger { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_TRIGGER_CONFIG; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - struct GpioParams { enum class Mode : uint8_t @@ -1626,19 +2702,19 @@ struct EventTrigger }; struct CombinationParams { - static const uint16_t LOGIC_NEVER = 0x0000; - static const uint16_t LOGIC_ALWAYS = 0xFFFF; - static const uint16_t LOGIC_NONE = 0x0001; - static const uint16_t LOGIC_OR = 0xFFFE; - static const uint16_t LOGIC_NAND = 0x7FFF; - static const uint16_t LOGIC_XOR_ONE = 0x0116; - static const uint16_t LOGIC_ONLY_A = 0x0002; - static const uint16_t LOGIC_ONLY_B = 0x0004; - static const uint16_t LOGIC_ONLY_C = 0x0010; - static const uint16_t LOGIC_ONLY_D = 0x0100; - static const uint16_t LOGIC_AND_AB = 0x8888; - static const uint16_t LOGIC_AB_OR_C = 0xF8F8; - static const uint16_t LOGIC_AND = 0x8000; + static constexpr const uint16_t LOGIC_NEVER = 0x0000; + static constexpr const uint16_t LOGIC_ALWAYS = 0xFFFF; + static constexpr const uint16_t LOGIC_NONE = 0x0001; + static constexpr const uint16_t LOGIC_OR = 0xFFFE; + static constexpr const uint16_t LOGIC_NAND = 0x7FFF; + static constexpr const uint16_t LOGIC_XOR_ONE = 0x0116; + static constexpr const uint16_t LOGIC_ONLY_A = 0x0002; + static constexpr const uint16_t LOGIC_ONLY_B = 0x0004; + static constexpr const uint16_t LOGIC_ONLY_C = 0x0010; + static constexpr const uint16_t LOGIC_ONLY_D = 0x0100; + 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; 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. @@ -1664,15 +2740,58 @@ struct EventTrigger Type type = static_cast(0); ///< Type of trigger to configure. Parameters parameters; + 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 + { + return std::make_tuple(instance,type,parameters); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(instance),std::ref(type),std::ref(parameters)); + } + + static EventTrigger create_sld_all(::mip::FunctionSelector function) + { + EventTrigger cmd; + cmd.function = function; + cmd.instance = 0; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_TRIGGER_CONFIG; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(instance),std::ref(type),std::ref(parameters)); + } }; }; void insert(Serializer& serializer, const EventTrigger& self); @@ -1690,11 +2809,12 @@ void extract(Serializer& serializer, EventTrigger::CombinationParams& self); void insert(Serializer& serializer, const EventTrigger::Response& self); void extract(Serializer& serializer, EventTrigger::Response& self); -CmdResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters); -CmdResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut); -CmdResult saveEventTrigger(C::mip_interface& device, uint8_t instance); -CmdResult loadEventTrigger(C::mip_interface& device, uint8_t instance); -CmdResult defaultEventTrigger(C::mip_interface& device, uint8_t instance); +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); +TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance); +TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1705,15 +2825,6 @@ CmdResult defaultEventTrigger(C::mip_interface& device, uint8_t instance); struct EventAction { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_ACTION_CONFIG; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - struct GpioParams { enum class Mode : uint8_t @@ -1758,16 +2869,59 @@ struct EventAction Type type = static_cast(0); ///< Type of action to configure. Parameters parameters; + 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 + { + return std::make_tuple(instance,trigger,type,parameters); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(instance),std::ref(trigger),std::ref(type),std::ref(parameters)); + } + + static EventAction create_sld_all(::mip::FunctionSelector function) + { + EventAction cmd; + cmd.function = function; + cmd.instance = 0; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_ACTION_CONFIG; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(instance),std::ref(trigger),std::ref(type),std::ref(parameters)); + } }; }; void insert(Serializer& serializer, const EventAction& self); @@ -1782,11 +2936,12 @@ void extract(Serializer& serializer, EventAction::MessageParams& self); void insert(Serializer& serializer, const EventAction::Response& self); void extract(Serializer& serializer, EventAction::Response& self); -CmdResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters); -CmdResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut); -CmdResult saveEventAction(C::mip_interface& device, uint8_t instance); -CmdResult loadEventAction(C::mip_interface& device, uint8_t instance); -CmdResult defaultEventAction(C::mip_interface& device, uint8_t instance); +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); +TypedResult loadEventAction(C::mip_interface& device, uint8_t instance); +TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1799,25 +2954,58 @@ CmdResult defaultEventAction(C::mip_interface& device, uint8_t instance); struct AccelBias { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_ACCEL_BIAS; + FunctionSelector function = static_cast(0); + Vector3f bias; ///< accelerometer bias in the sensor frame (x,y,z) [g] + + 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 + { + return std::make_tuple(bias); + } - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + auto as_tuple() + { + return std::make_tuple(std::ref(bias)); + } - FunctionSelector function = static_cast(0); - float bias[3] = {0}; ///< accelerometer bias in the sensor frame (x,y,z) [g] + static AccelBias create_sld_all(::mip::FunctionSelector function) + { + AccelBias cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_ACCEL_BIAS_VECTOR; + 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 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] - float bias[3] = {0}; ///< accelerometer bias in the sensor frame (x,y,z) [g] + auto as_tuple() + { + return std::make_tuple(std::ref(bias)); + } }; }; void insert(Serializer& serializer, const AccelBias& self); @@ -1826,11 +3014,12 @@ void extract(Serializer& serializer, AccelBias& self); void insert(Serializer& serializer, const AccelBias::Response& self); void extract(Serializer& serializer, AccelBias::Response& self); -CmdResult writeAccelBias(C::mip_interface& device, const float* bias); -CmdResult readAccelBias(C::mip_interface& device, float* biasOut); -CmdResult saveAccelBias(C::mip_interface& device); -CmdResult loadAccelBias(C::mip_interface& device); -CmdResult defaultAccelBias(C::mip_interface& device); +TypedResult writeAccelBias(C::mip_interface& device, const float* bias); +TypedResult readAccelBias(C::mip_interface& device, float* biasOut); +TypedResult saveAccelBias(C::mip_interface& device); +TypedResult loadAccelBias(C::mip_interface& device); +TypedResult defaultAccelBias(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1843,25 +3032,58 @@ CmdResult defaultAccelBias(C::mip_interface& device); struct GyroBias { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GYRO_BIAS; + FunctionSelector function = static_cast(0); + Vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + + 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 + { + return std::make_tuple(bias); + } - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + auto as_tuple() + { + return std::make_tuple(std::ref(bias)); + } - FunctionSelector function = static_cast(0); - float bias[3] = {0}; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + static GyroBias create_sld_all(::mip::FunctionSelector function) + { + GyroBias cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GYRO_BIAS_VECTOR; + 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 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] - float bias[3] = {0}; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + auto as_tuple() + { + return std::make_tuple(std::ref(bias)); + } }; }; void insert(Serializer& serializer, const GyroBias& self); @@ -1870,11 +3092,12 @@ void extract(Serializer& serializer, GyroBias& self); void insert(Serializer& serializer, const GyroBias::Response& self); void extract(Serializer& serializer, GyroBias::Response& self); -CmdResult writeGyroBias(C::mip_interface& device, const float* bias); -CmdResult readGyroBias(C::mip_interface& device, float* biasOut); -CmdResult saveGyroBias(C::mip_interface& device); -CmdResult loadGyroBias(C::mip_interface& device); -CmdResult defaultGyroBias(C::mip_interface& device); +TypedResult writeGyroBias(C::mip_interface& device, const float* bias); +TypedResult readGyroBias(C::mip_interface& device, float* biasOut); +TypedResult saveGyroBias(C::mip_interface& device); +TypedResult loadGyroBias(C::mip_interface& device); +TypedResult defaultGyroBias(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1890,20 +3113,44 @@ CmdResult defaultGyroBias(C::mip_interface& device); struct CaptureGyroBias { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CAPTURE_GYRO_BIAS; + uint16_t averaging_time_ms = 0; ///< Averaging time [milliseconds] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint16_t averaging_time_ms = 0; ///< Averaging time [milliseconds] + 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 + { + return std::make_tuple(averaging_time_ms); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(averaging_time_ms)); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GYRO_BIAS_VECTOR; + 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 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] - float bias[3] = {0}; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + auto as_tuple() + { + return std::make_tuple(std::ref(bias)); + } }; }; void insert(Serializer& serializer, const CaptureGyroBias& self); @@ -1912,7 +3159,8 @@ void extract(Serializer& serializer, CaptureGyroBias& self); void insert(Serializer& serializer, const CaptureGyroBias::Response& self); void extract(Serializer& serializer, CaptureGyroBias::Response& self); -CmdResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut); +TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1929,25 +3177,58 @@ CmdResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, fl struct MagHardIronOffset { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_HARD_IRON_OFFSET; + FunctionSelector function = static_cast(0); + Vector3f offset; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] + + 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 + { + return std::make_tuple(offset); + } - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } - FunctionSelector function = static_cast(0); - float offset[3] = {0}; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] + static MagHardIronOffset create_sld_all(::mip::FunctionSelector function) + { + MagHardIronOffset cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_HARD_IRON_OFFSET_VECTOR; + 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 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] - float offset[3] = {0}; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } }; }; void insert(Serializer& serializer, const MagHardIronOffset& self); @@ -1956,11 +3237,12 @@ void extract(Serializer& serializer, MagHardIronOffset& self); void insert(Serializer& serializer, const MagHardIronOffset::Response& self); void extract(Serializer& serializer, MagHardIronOffset::Response& self); -CmdResult writeMagHardIronOffset(C::mip_interface& device, const float* offset); -CmdResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut); -CmdResult saveMagHardIronOffset(C::mip_interface& device); -CmdResult loadMagHardIronOffset(C::mip_interface& device); -CmdResult defaultMagHardIronOffset(C::mip_interface& device); +TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset); +TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut); +TypedResult saveMagHardIronOffset(C::mip_interface& device); +TypedResult loadMagHardIronOffset(C::mip_interface& device); +TypedResult defaultMagHardIronOffset(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1981,25 +3263,58 @@ CmdResult defaultMagHardIronOffset(C::mip_interface& device); struct MagSoftIronMatrix { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SOFT_IRON_MATRIX; + FunctionSelector function = static_cast(0); + Matrix3f offset; ///< soft iron matrix [dimensionless] + + 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 + { + return std::make_tuple(offset); + } - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } - FunctionSelector function = static_cast(0); - float offset[9] = {0}; ///< soft iron matrix [dimensionless] + static MagSoftIronMatrix create_sld_all(::mip::FunctionSelector function) + { + MagSoftIronMatrix cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SOFT_IRON_COMP_MATRIX; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Matrix3f offset; ///< soft iron matrix [dimensionless] - float offset[9] = {0}; ///< soft iron matrix [dimensionless] + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } }; }; void insert(Serializer& serializer, const MagSoftIronMatrix& self); @@ -2008,11 +3323,88 @@ void extract(Serializer& serializer, MagSoftIronMatrix& self); void insert(Serializer& serializer, const MagSoftIronMatrix::Response& self); void extract(Serializer& serializer, MagSoftIronMatrix::Response& self); -CmdResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset); -CmdResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut); -CmdResult saveMagSoftIronMatrix(C::mip_interface& device); -CmdResult loadMagSoftIronMatrix(C::mip_interface& device); -CmdResult defaultMagSoftIronMatrix(C::mip_interface& device); +TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset); +TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut); +TypedResult saveMagSoftIronMatrix(C::mip_interface& device); +TypedResult loadMagSoftIronMatrix(C::mip_interface& device); +TypedResult defaultMagSoftIronMatrix(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_3dm_coning_sculling_enable (0x0C,0x3E) Coning Sculling Enable [CPP] +/// Controls the Coning and Sculling Compenstation setting. +/// +///@{ + +struct ConingScullingEnable +{ + FunctionSelector function = static_cast(0); + bool enable = 0; ///< If true, coning and sculling compensation is enabled. + + 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 + { + return std::make_tuple(enable); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } + + static ConingScullingEnable create_sld_all(::mip::FunctionSelector function) + { + ConingScullingEnable cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(enable)); + } + }; +}; +void insert(Serializer& serializer, const ConingScullingEnable& self); +void extract(Serializer& serializer, ConingScullingEnable& self); + +void insert(Serializer& serializer, const ConingScullingEnable::Response& self); +void extract(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); +TypedResult loadConingScullingEnable(C::mip_interface& device); +TypedResult defaultConingScullingEnable(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -2047,29 +3439,62 @@ CmdResult defaultMagSoftIronMatrix(C::mip_interface& device); struct Sensor2VehicleTransformEuler { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR2VEHICLE_TRANSFORM_EUL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] + 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 + { + return std::make_tuple(roll,pitch,yaw); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); + } + + static Sensor2VehicleTransformEuler create_sld_all(::mip::FunctionSelector function) + { + Sensor2VehicleTransformEuler cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR2VEHICLE_TRANSFORM_EUL; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); + } }; }; void insert(Serializer& serializer, const Sensor2VehicleTransformEuler& self); @@ -2078,11 +3503,12 @@ void extract(Serializer& serializer, Sensor2VehicleTransformEuler& self); void insert(Serializer& serializer, const Sensor2VehicleTransformEuler::Response& self); void extract(Serializer& serializer, Sensor2VehicleTransformEuler::Response& self); -CmdResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw); -CmdResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); -CmdResult saveSensor2VehicleTransformEuler(C::mip_interface& device); -CmdResult loadSensor2VehicleTransformEuler(C::mip_interface& device); -CmdResult defaultSensor2VehicleTransformEuler(C::mip_interface& device); +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); +TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device); +TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -2096,7 +3522,7 @@ CmdResult defaultSensor2VehicleTransformEuler(C::mip_interface& device); /// EQSTART p^{veh} = q^{-1} p^{sen} q EQEND
/// /// Where:
-/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion desrcribing the transformation.
+/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
/// EQSTART 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.
/// EQSTART 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.
/// @@ -2125,25 +3551,58 @@ CmdResult defaultSensor2VehicleTransformEuler(C::mip_interface& device); struct Sensor2VehicleTransformQuaternion { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR2VEHICLE_TRANSFORM_QUAT; + FunctionSelector function = static_cast(0); + Quatf q; ///< Unit length quaternion representing transform [w, i, j, k] + + 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 + { + return std::make_tuple(q); + } - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + auto as_tuple() + { + return std::make_tuple(std::ref(q)); + } - FunctionSelector function = static_cast(0); - float q[4] = {0}; ///< Unit length quaternion representing transform [w, i, j, k] + static Sensor2VehicleTransformQuaternion create_sld_all(::mip::FunctionSelector function) + { + Sensor2VehicleTransformQuaternion cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT; + 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"; - float q[4] = {0}; ///< Unit length quaternion representing transform [w, i, j, k] + 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 as_tuple() + { + return std::make_tuple(std::ref(q)); + } }; }; void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion& self); @@ -2152,11 +3611,12 @@ void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion& self); void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion::Response& self); void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion::Response& self); -CmdResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q); -CmdResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut); -CmdResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device); -CmdResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device); -CmdResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device); +TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q); +TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut); +TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device); +TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device); +TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -2197,25 +3657,58 @@ CmdResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device); struct Sensor2VehicleTransformDcm { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR2VEHICLE_TRANSFORM_DCM; + FunctionSelector function = static_cast(0); + Matrix3f dcm; ///< 3 x 3 direction cosine matrix, stored in row-major order + + 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 + { + return std::make_tuple(dcm); + } - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + auto as_tuple() + { + return std::make_tuple(std::ref(dcm)); + } - FunctionSelector function = static_cast(0); - float dcm[9] = {0}; ///< 3 x 3 direction cosine matrix, stored in row-major order + static Sensor2VehicleTransformDcm create_sld_all(::mip::FunctionSelector function) + { + Sensor2VehicleTransformDcm cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR2VEHICLE_TRANSFORM_DCM; + 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"; - float dcm[9] = {0}; ///< 3 x 3 direction cosine matrix, stored in row-major order + 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 as_tuple() + { + return std::make_tuple(std::ref(dcm)); + } }; }; void insert(Serializer& serializer, const Sensor2VehicleTransformDcm& self); @@ -2224,11 +3717,12 @@ void extract(Serializer& serializer, Sensor2VehicleTransformDcm& self); void insert(Serializer& serializer, const Sensor2VehicleTransformDcm::Response& self); void extract(Serializer& serializer, Sensor2VehicleTransformDcm::Response& self); -CmdResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm); -CmdResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut); -CmdResult saveSensor2VehicleTransformDcm(C::mip_interface& device); -CmdResult loadSensor2VehicleTransformDcm(C::mip_interface& device); -CmdResult defaultSensor2VehicleTransformDcm(C::mip_interface& device); +TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm); +TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut); +TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device); +TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device); +TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -2236,38 +3730,71 @@ CmdResult defaultSensor2VehicleTransformDcm(C::mip_interface& device); /// 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), -/// and to correct for heading using the magnetomer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field). +/// and to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field). /// Pitch/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. /// ///@{ struct ComplementaryFilter { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_LEGACY_COMP_FILTER; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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] + 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 + { + return std::make_tuple(pitch_roll_enable,heading_enable,pitch_roll_time_constant,heading_time_constant); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(pitch_roll_enable),std::ref(heading_enable),std::ref(pitch_roll_time_constant),std::ref(heading_time_constant)); + } + + static ComplementaryFilter create_sld_all(::mip::FunctionSelector function) + { + ComplementaryFilter cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_LEGACY_COMP_FILTER; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(pitch_roll_enable),std::ref(heading_enable),std::ref(pitch_roll_time_constant),std::ref(heading_time_constant)); + } }; }; void insert(Serializer& serializer, const ComplementaryFilter& self); @@ -2276,11 +3803,12 @@ void extract(Serializer& serializer, ComplementaryFilter& self); void insert(Serializer& serializer, const ComplementaryFilter::Response& self); void extract(Serializer& serializer, ComplementaryFilter::Response& self); -CmdResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant); -CmdResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut); -CmdResult saveComplementaryFilter(C::mip_interface& device); -CmdResult loadComplementaryFilter(C::mip_interface& device); -CmdResult defaultComplementaryFilter(C::mip_interface& device); +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); +TypedResult loadComplementaryFilter(C::mip_interface& device); +TypedResult defaultComplementaryFilter(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -2288,7 +3816,7 @@ CmdResult defaultComplementaryFilter(C::mip_interface& device); /// Changes the IMU sensor gain. /// /// This allows you to optimize the range to get the best accuracy and performance -/// while minimizing overrange events. +/// while minimizing over-range events. /// /// Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine /// the appropriate setting value for your application. Using values other than @@ -2298,27 +3826,61 @@ CmdResult defaultComplementaryFilter(C::mip_interface& device); struct SensorRange { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR_RANGE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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. + 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 + { + return std::make_tuple(sensor,setting); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(sensor),std::ref(setting)); + } + + static SensorRange create_sld_all(::mip::FunctionSelector function) + { + SensorRange cmd; + cmd.function = function; + cmd.sensor = ::mip::commands_3dm::SensorRangeType::ALL; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR_RANGE; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(sensor),std::ref(setting)); + } }; }; void insert(Serializer& serializer, const SensorRange& self); @@ -2327,11 +3889,12 @@ void extract(Serializer& serializer, SensorRange& self); void insert(Serializer& serializer, const SensorRange::Response& self); void extract(Serializer& serializer, SensorRange::Response& self); -CmdResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting); -CmdResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut); -CmdResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor); -CmdResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor); -CmdResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor); +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); +TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor); +TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -2345,11 +3908,6 @@ CmdResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor); struct CalibratedSensorRanges { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CALIBRATED_RANGES; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct Entry { uint8_t setting = 0; ///< The value used in the 3DM Sensor Range command and response. @@ -2358,15 +3916,44 @@ struct CalibratedSensorRanges }; SensorRangeType sensor = static_cast(0); ///< The sensor to query. Cannot be ALL. + 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 + { + return std::make_tuple(sensor); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(sensor)); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_CALIBRATED_RANGES; - + 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 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 as_tuple() + { + return std::make_tuple(std::ref(sensor),std::ref(num_ranges),std::ref(ranges)); + } }; }; void insert(Serializer& serializer, const CalibratedSensorRanges& self); @@ -2378,7 +3965,107 @@ void extract(Serializer& serializer, CalibratedSensorRanges::Entry& self); void insert(Serializer& serializer, const CalibratedSensorRanges::Response& self); void extract(Serializer& serializer, CalibratedSensorRanges::Response& self); -CmdResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut); +TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_3dm_lowpass_filter (0x0C,0x54) Lowpass Filter [CPP] +/// 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. +/// +/// If set to automatic mode, the frequency will track half of the transmission rate +/// of the target descriptor according to the configured message format (0x0C,0x0F). +/// For example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter would +/// be set to 50 Hz. Changing the message format to 200 Hz would automatically adjust the +/// filter to 100 Hz. +/// +/// For WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptor +/// may be 0x00 to set, save, load, or reset the setting for all supported descriptors. The +/// field descriptor must be 0x00 if the descriptor set is 0x00. +/// +/// +///@{ + +struct LowpassFilter +{ + 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. + 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. + + 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 + { + return std::make_tuple(desc_set,field_desc,enable,manual,frequency); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(field_desc),std::ref(enable),std::ref(manual),std::ref(frequency)); + } + + static LowpassFilter create_sld_all(::mip::FunctionSelector function) + { + LowpassFilter cmd; + cmd.function = function; + cmd.desc_set = 0; + cmd.field_desc = 0; + return cmd; + } + + 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; + 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. + + + auto as_tuple() + { + return std::make_tuple(std::ref(desc_set),std::ref(field_desc),std::ref(enable),std::ref(manual),std::ref(frequency)); + } + }; +}; +void insert(Serializer& serializer, const LowpassFilter& self); +void extract(Serializer& serializer, LowpassFilter& self); + +void insert(Serializer& serializer, const LowpassFilter::Response& self); +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); +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); +TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc); +TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc); + ///@} /// diff --git a/src/mip/definitions/commands_aiding.c b/src/mip/definitions/commands_aiding.c new file mode 100644 index 000000000..dcd292f3d --- /dev/null +++ b/src/mip/definitions/commands_aiding.c @@ -0,0 +1,978 @@ + +#include "commands_aiding.h" + +#include "../utils/serialization.h" +#include "../mip_interface.h" + +#include + + +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { + +#endif // __cplusplus +struct mip_interface; +struct mip_serializer; +struct mip_field; + + +//////////////////////////////////////////////////////////////////////////////// +// Shared Type Definitions +//////////////////////////////////////////////////////////////////////////////// + +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); + +} +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); + +} + +void insert_mip_time_timebase(struct mip_serializer* serializer, const mip_time_timebase self) +{ + 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); + *self = tmp; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Mip Fields +//////////////////////////////////////////////////////////////////////////////// + +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); + + if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) + { + insert_mip_aiding_frame_config_command_format(serializer, self->format); + + } + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_bool(serializer, self->tracking_enabled); + + for(unsigned int i=0; i < 3; i++) + 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_command(mip_serializer* serializer, mip_aiding_frame_config_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + extract_u8(serializer, &self->frame_id); + + if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) + { + extract_mip_aiding_frame_config_command_format(serializer, &self->format); + + } + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_bool(serializer, &self->tracking_enabled); + + for(unsigned int i=0; i < 3; i++) + 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_response(mip_serializer* serializer, const mip_aiding_frame_config_response* self) +{ + insert_u8(serializer, self->frame_id); + + insert_mip_aiding_frame_config_command_format(serializer, self->format); + + insert_bool(serializer, self->tracking_enabled); + + for(unsigned int i=0; i < 3; i++) + 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(mip_serializer* serializer, mip_aiding_frame_config_response* self) +{ + extract_u8(serializer, &self->frame_id); + + extract_mip_aiding_frame_config_command_format(serializer, &self->format); + + extract_bool(serializer, &self->tracking_enabled); + + for(unsigned int i=0; i < 3; i++) + 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(struct mip_serializer* serializer, const mip_aiding_frame_config_command_format self) +{ + 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); + *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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_u8(&serializer, frame_id); + + insert_mip_aiding_frame_config_command_format(&serializer, format); + + insert_bool(&serializer, tracking_enabled); + + assert(translation || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, translation[i]); + + if( format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) + { + insert_mip_vector3f(&serializer, rotation->euler); + + } + if( format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION ) + { + insert_mip_quatf(&serializer, rotation->quaternion); + + } + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + insert_u8(&serializer, frame_id); + + insert_mip_aiding_frame_config_command_format(&serializer, format); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + extract_u8(&deserializer, &frame_id); + + extract_mip_aiding_frame_config_command_format(&deserializer, &format); + + assert(tracking_enabled_out); + 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]); + + if( format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) + { + extract_mip_vector3f(&deserializer, rotation_out->euler); + + } + if( format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION ) + { + extract_mip_quatf(&deserializer, rotation_out->quaternion); + + } + if( mip_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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + insert_u8(&serializer, frame_id); + + assert(mip_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)); +} +mip_cmd_result mip_aiding_load_frame_config(struct mip_interface* device, uint8_t frame_id) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + insert_u8(&serializer, frame_id); + + assert(mip_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)); +} +mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uint8_t frame_id) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + insert_u8(&serializer, frame_id); + + assert(mip_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)); +} +void insert_mip_aiding_echo_control_command(mip_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_echo_control_command_mode(serializer, self->mode); + + } +} +void extract_mip_aiding_echo_control_command(mip_serializer* serializer, mip_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); + + } +} + +void insert_mip_aiding_echo_control_response(mip_serializer* serializer, const mip_aiding_echo_control_response* self) +{ + insert_mip_aiding_echo_control_command_mode(serializer, self->mode); + +} +void extract_mip_aiding_echo_control_response(mip_serializer* serializer, mip_aiding_echo_control_response* self) +{ + extract_mip_aiding_echo_control_command_mode(serializer, &self->mode); + +} + +void insert_mip_aiding_echo_control_command_mode(struct mip_serializer* serializer, const mip_aiding_echo_control_command_mode self) +{ + insert_u8(serializer, (uint8_t)(self)); +} +void extract_mip_aiding_echo_control_command_mode(struct mip_serializer* serializer, mip_aiding_echo_control_command_mode* self) +{ + uint8_t tmp = 0; + extract_u8(serializer, &tmp); + *self = tmp; +} + +mip_cmd_result mip_aiding_write_echo_control(struct mip_interface* device, mip_aiding_echo_control_command_mode mode) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_aiding_echo_control_command_mode(&serializer, mode); + + assert(mip_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)); +} +mip_cmd_result mip_aiding_read_echo_control(struct mip_interface* device, mip_aiding_echo_control_command_mode* mode_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(mode_out); + extract_mip_aiding_echo_control_command_mode(&deserializer, mode_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_aiding_save_echo_control(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_aiding_load_echo_control(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_aiding_default_echo_control(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_aiding_pos_ecef_command(mip_serializer* serializer, const mip_aiding_pos_ecef_command* self) +{ + insert_mip_time(serializer, &self->time); + + insert_u8(serializer, self->frame_id); + + for(unsigned int i=0; i < 3; i++) + insert_double(serializer, self->position[i]); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->uncertainty[i]); + + insert_mip_aiding_pos_ecef_command_valid_flags(serializer, self->valid_flags); + +} +void extract_mip_aiding_pos_ecef_command(mip_serializer* serializer, mip_aiding_pos_ecef_command* self) +{ + extract_mip_time(serializer, &self->time); + + extract_u8(serializer, &self->frame_id); + + for(unsigned int i=0; i < 3; i++) + extract_double(serializer, &self->position[i]); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->uncertainty[i]); + + extract_mip_aiding_pos_ecef_command_valid_flags(serializer, &self->valid_flags); + +} + +void insert_mip_aiding_pos_ecef_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_pos_ecef_command_valid_flags self) +{ + insert_u16(serializer, (uint16_t)(self)); +} +void extract_mip_aiding_pos_ecef_command_valid_flags(struct mip_serializer* serializer, mip_aiding_pos_ecef_command_valid_flags* self) +{ + uint16_t tmp = 0; + extract_u16(serializer, &tmp); + *self = tmp; +} + +mip_cmd_result mip_aiding_pos_ecef(struct 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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + assert(position || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_double(&serializer, position[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, uncertainty[i]); + + insert_mip_aiding_pos_ecef_command_valid_flags(&serializer, valid_flags); + + assert(mip_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)); +} +void insert_mip_aiding_pos_llh_command(mip_serializer* serializer, const mip_aiding_pos_llh_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); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->uncertainty[i]); + + insert_mip_aiding_pos_llh_command_valid_flags(serializer, self->valid_flags); + +} +void extract_mip_aiding_pos_llh_command(mip_serializer* serializer, mip_aiding_pos_llh_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); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->uncertainty[i]); + + extract_mip_aiding_pos_llh_command_valid_flags(serializer, &self->valid_flags); + +} + +void insert_mip_aiding_pos_llh_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_pos_llh_command_valid_flags self) +{ + insert_u16(serializer, (uint16_t)(self)); +} +void extract_mip_aiding_pos_llh_command_valid_flags(struct mip_serializer* serializer, mip_aiding_pos_llh_command_valid_flags* self) +{ + uint16_t tmp = 0; + extract_u16(serializer, &tmp); + *self = tmp; +} + +mip_cmd_result mip_aiding_pos_llh(struct 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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + insert_double(&serializer, latitude); + + insert_double(&serializer, longitude); + + insert_double(&serializer, height); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, uncertainty[i]); + + insert_mip_aiding_pos_llh_command_valid_flags(&serializer, valid_flags); + + assert(mip_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)); +} +void insert_mip_aiding_height_above_ellipsoid_command(mip_serializer* serializer, const mip_aiding_height_above_ellipsoid_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); + +} +void extract_mip_aiding_height_above_ellipsoid_command(mip_serializer* serializer, mip_aiding_height_above_ellipsoid_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); + +} + +mip_cmd_result mip_aiding_height_above_ellipsoid(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + insert_float(&serializer, height); + + insert_float(&serializer, uncertainty); + + insert_u16(&serializer, valid_flags); + + assert(mip_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)mip_serializer_length(&serializer)); +} +void insert_mip_aiding_vel_ecef_command(mip_serializer* serializer, const mip_aiding_vel_ecef_command* self) +{ + insert_mip_time(serializer, &self->time); + + insert_u8(serializer, self->frame_id); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->velocity[i]); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->uncertainty[i]); + + insert_mip_aiding_vel_ecef_command_valid_flags(serializer, self->valid_flags); + +} +void extract_mip_aiding_vel_ecef_command(mip_serializer* serializer, mip_aiding_vel_ecef_command* self) +{ + extract_mip_time(serializer, &self->time); + + extract_u8(serializer, &self->frame_id); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->velocity[i]); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->uncertainty[i]); + + extract_mip_aiding_vel_ecef_command_valid_flags(serializer, &self->valid_flags); + +} + +void insert_mip_aiding_vel_ecef_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vel_ecef_command_valid_flags self) +{ + insert_u16(serializer, (uint16_t)(self)); +} +void extract_mip_aiding_vel_ecef_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vel_ecef_command_valid_flags* self) +{ + uint16_t tmp = 0; + extract_u16(serializer, &tmp); + *self = tmp; +} + +mip_cmd_result mip_aiding_vel_ecef(struct 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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + assert(velocity || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, velocity[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, uncertainty[i]); + + insert_mip_aiding_vel_ecef_command_valid_flags(&serializer, valid_flags); + + assert(mip_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)); +} +void insert_mip_aiding_vel_ned_command(mip_serializer* serializer, const mip_aiding_vel_ned_command* self) +{ + insert_mip_time(serializer, &self->time); + + insert_u8(serializer, self->frame_id); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->velocity[i]); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->uncertainty[i]); + + insert_mip_aiding_vel_ned_command_valid_flags(serializer, self->valid_flags); + +} +void extract_mip_aiding_vel_ned_command(mip_serializer* serializer, mip_aiding_vel_ned_command* self) +{ + extract_mip_time(serializer, &self->time); + + extract_u8(serializer, &self->frame_id); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->velocity[i]); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->uncertainty[i]); + + extract_mip_aiding_vel_ned_command_valid_flags(serializer, &self->valid_flags); + +} + +void insert_mip_aiding_vel_ned_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vel_ned_command_valid_flags self) +{ + insert_u16(serializer, (uint16_t)(self)); +} +void extract_mip_aiding_vel_ned_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vel_ned_command_valid_flags* self) +{ + uint16_t tmp = 0; + extract_u16(serializer, &tmp); + *self = tmp; +} + +mip_cmd_result mip_aiding_vel_ned(struct 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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + assert(velocity || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, velocity[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, uncertainty[i]); + + insert_mip_aiding_vel_ned_command_valid_flags(&serializer, valid_flags); + + assert(mip_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)); +} +void insert_mip_aiding_vel_body_frame_command(mip_serializer* serializer, const mip_aiding_vel_body_frame_command* self) +{ + insert_mip_time(serializer, &self->time); + + insert_u8(serializer, self->frame_id); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->velocity[i]); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->uncertainty[i]); + + insert_mip_aiding_vel_body_frame_command_valid_flags(serializer, self->valid_flags); + +} +void extract_mip_aiding_vel_body_frame_command(mip_serializer* serializer, mip_aiding_vel_body_frame_command* self) +{ + extract_mip_time(serializer, &self->time); + + extract_u8(serializer, &self->frame_id); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->velocity[i]); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->uncertainty[i]); + + extract_mip_aiding_vel_body_frame_command_valid_flags(serializer, &self->valid_flags); + +} + +void insert_mip_aiding_vel_body_frame_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vel_body_frame_command_valid_flags self) +{ + insert_u16(serializer, (uint16_t)(self)); +} +void extract_mip_aiding_vel_body_frame_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vel_body_frame_command_valid_flags* self) +{ + uint16_t tmp = 0; + extract_u16(serializer, &tmp); + *self = tmp; +} + +mip_cmd_result mip_aiding_vel_body_frame(struct 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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + assert(velocity || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, velocity[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, uncertainty[i]); + + insert_mip_aiding_vel_body_frame_command_valid_flags(&serializer, valid_flags); + + assert(mip_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)mip_serializer_length(&serializer)); +} +void insert_mip_aiding_heading_true_command(mip_serializer* serializer, const mip_aiding_heading_true_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); + +} +void extract_mip_aiding_heading_true_command(mip_serializer* serializer, mip_aiding_heading_true_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); + +} + +mip_cmd_result mip_aiding_heading_true(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + insert_float(&serializer, heading); + + insert_float(&serializer, uncertainty); + + insert_u16(&serializer, valid_flags); + + assert(mip_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)); +} +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); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->magnetic_field[i]); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->uncertainty[i]); + + 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) +{ + extract_mip_time(serializer, &self->time); + + extract_u8(serializer, &self->frame_id); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->magnetic_field[i]); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->uncertainty[i]); + + extract_mip_aiding_magnetic_field_command_valid_flags(serializer, &self->valid_flags); + +} + +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)); +} +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); + *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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + assert(magnetic_field || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, magnetic_field[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, uncertainty[i]); + + insert_mip_aiding_magnetic_field_command_valid_flags(&serializer, valid_flags); + + assert(mip_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)); +} +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); + +} +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); + +} + +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + assert(time); + insert_mip_time(&serializer, time); + + insert_u8(&serializer, frame_id); + + insert_float(&serializer, pressure); + + insert_float(&serializer, uncertainty); + + insert_u16(&serializer, valid_flags); + + assert(mip_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)); +} + +#ifdef __cplusplus +} // namespace C +} // namespace mip +} // extern "C" +#endif // __cplusplus + diff --git a/src/mip/definitions/commands_aiding.cpp b/src/mip/definitions/commands_aiding.cpp new file mode 100644 index 000000000..b7e1b106b --- /dev/null +++ b/src/mip/definitions/commands_aiding.cpp @@ -0,0 +1,838 @@ + +#include "commands_aiding.hpp" + +#include "../utils/serialization.h" +#include "../mip_interface.h" + +#include + + +namespace mip { +class Serializer; + +namespace C { +struct mip_interface; +} // namespace C + +namespace commands_aiding { + +using ::mip::insert; +using ::mip::extract; +using namespace ::mip::C; + +//////////////////////////////////////////////////////////////////////////////// +// Shared Type Definitions +//////////////////////////////////////////////////////////////////////////////// + +void insert(Serializer& serializer, const Time& self) +{ + insert(serializer, self.timebase); + + insert(serializer, self.reserved); + + insert(serializer, self.nanoseconds); + +} +void extract(Serializer& serializer, Time& self) +{ + extract(serializer, self.timebase); + + extract(serializer, self.reserved); + + extract(serializer, self.nanoseconds); + +} + + +//////////////////////////////////////////////////////////////////////////////// +// Mip Fields +//////////////////////////////////////////////////////////////////////////////// + +void insert(Serializer& serializer, const FrameConfig& self) +{ + insert(serializer, self.function); + + insert(serializer, self.frame_id); + + if( self.function == FunctionSelector::WRITE || self.function == FunctionSelector::READ ) + { + insert(serializer, self.format); + + } + if( self.function == FunctionSelector::WRITE ) + { + 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(Serializer& serializer, FrameConfig& self) +{ + extract(serializer, self.function); + + extract(serializer, self.frame_id); + + if( self.function == FunctionSelector::WRITE || self.function == FunctionSelector::READ ) + { + extract(serializer, self.format); + + } + if( self.function == FunctionSelector::WRITE ) + { + 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); + + } + } +} + +void insert(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(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, frameId); + + insert(serializer, format); + + insert(serializer, trackingEnabled); + + assert(translation || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, translation[i]); + + if( format == FrameConfig::Format::EULER ) + { + insert(serializer, rotation.euler); + + } + if( format == FrameConfig::Format::QUATERNION ) + { + insert(serializer, rotation.quaternion); + + } + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +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)); + + insert(serializer, FunctionSelector::READ); + insert(serializer, frameId); + + insert(serializer, 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)mip_serializer_length(&serializer), REPLY_FRAME_CONFIG, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + extract(deserializer, frameId); + + extract(deserializer, format); + + assert(trackingEnabledOut); + extract(deserializer, *trackingEnabledOut); + + assert(translationOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, translationOut[i]); + + if( format == FrameConfig::Format::EULER ) + { + extract(deserializer, rotationOut->euler); + + } + if( format == FrameConfig::Format::QUATERNION ) + { + extract(deserializer, rotationOut->quaternion); + + } + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frameId) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const EchoControl& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.mode); + + } +} +void extract(Serializer& serializer, EchoControl& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.mode); + + } +} + +void insert(Serializer& serializer, const EchoControl::Response& self) +{ + insert(serializer, self.mode); + +} +void extract(Serializer& serializer, EchoControl::Response& self) +{ + extract(serializer, self.mode); + +} + +TypedResult writeEchoControl(C::mip_interface& device, EchoControl::Mode mode) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_ECHO_CONTROL, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(modeOut); + extract(deserializer, *modeOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveEchoControl(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadEchoControl(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultEchoControl(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const PosEcef& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.position[i]); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.uncertainty[i]); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, PosEcef& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.position[i]); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.uncertainty[i]); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + assert(position || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, position[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, uncertainty[i]); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const PosLlh& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + insert(serializer, self.latitude); + + insert(serializer, self.longitude); + + insert(serializer, self.height); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.uncertainty[i]); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, PosLlh& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + extract(serializer, self.latitude); + + extract(serializer, self.longitude); + + extract(serializer, self.height); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.uncertainty[i]); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + insert(serializer, latitude); + + insert(serializer, longitude); + + insert(serializer, height); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, uncertainty[i]); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const HeightAboveEllipsoid& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + insert(serializer, self.height); + + insert(serializer, self.uncertainty); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, HeightAboveEllipsoid& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + extract(serializer, self.height); + + extract(serializer, self.uncertainty); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + insert(serializer, height); + + insert(serializer, uncertainty); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const VelEcef& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.velocity[i]); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.uncertainty[i]); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, VelEcef& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.velocity[i]); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.uncertainty[i]); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + assert(velocity || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, velocity[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, uncertainty[i]); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const VelNed& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.velocity[i]); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.uncertainty[i]); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, VelNed& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.velocity[i]); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.uncertainty[i]); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + assert(velocity || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, velocity[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, uncertainty[i]); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const VelBodyFrame& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.velocity[i]); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.uncertainty[i]); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, VelBodyFrame& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.velocity[i]); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.uncertainty[i]); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + assert(velocity || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, velocity[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, uncertainty[i]); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_BODY_FRAME, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const HeadingTrue& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + insert(serializer, self.heading); + + insert(serializer, self.uncertainty); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, HeadingTrue& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + extract(serializer, self.heading); + + extract(serializer, self.uncertainty); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + insert(serializer, heading); + + insert(serializer, uncertainty); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const MagneticField& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.magnetic_field[i]); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.uncertainty[i]); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, MagneticField& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.magnetic_field[i]); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.uncertainty[i]); + + extract(serializer, self.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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, time); + + insert(serializer, frameId); + + assert(magneticField || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, magneticField[i]); + + assert(uncertainty || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, uncertainty[i]); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const Pressure& self) +{ + insert(serializer, self.time); + + insert(serializer, self.frame_id); + + insert(serializer, self.pressure); + + insert(serializer, self.uncertainty); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, Pressure& self) +{ + extract(serializer, self.time); + + extract(serializer, self.frame_id); + + extract(serializer, self.pressure); + + extract(serializer, self.uncertainty); + + extract(serializer, self.valid_flags); + +} + +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)); + + insert(serializer, time); + + insert(serializer, frameId); + + insert(serializer, pressure); + + insert(serializer, uncertainty); + + insert(serializer, validFlags); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} + +} // namespace commands_aiding +} // namespace mip + diff --git a/src/mip/definitions/commands_aiding.h b/src/mip/definitions/commands_aiding.h new file mode 100644 index 000000000..51d92b67e --- /dev/null +++ b/src/mip/definitions/commands_aiding.h @@ -0,0 +1,486 @@ +#pragma once + +#include "common.h" +#include "descriptors.h" +#include "../mip_result.h" + +#include +#include +#include + +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { + +#endif // __cplusplus +struct mip_interface; +struct mip_serializer; +struct mip_field; + +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup MipCommands_c MIP Commands [C] +///@{ +///@defgroup aiding_commands_c Aiding Commands [C] +/// +///@{ + +//////////////////////////////////////////////////////////////////////////////// +// Descriptors +//////////////////////////////////////////////////////////////////////////////// + +enum +{ + 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_REPLY_DESC_AIDING_FRAME_CONFIG = 0x81, + MIP_REPLY_DESC_AIDING_ECHO_CONTROL = 0x9F, +}; + +//////////////////////////////////////////////////////////////////////////////// +// 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. + +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(struct mip_serializer* serializer, const mip_time* self); +void extract_mip_time(struct mip_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); + + +//////////////////////////////////////////////////////////////////////////////// +// Mip Fields +//////////////////////////////////////////////////////////////////////////////// + +//////////////////////////////////////////////////////////////////////////////// +///@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) +/// +/// This transform satisfies the following relationship: +/// +/// EQSTART p^{veh} = R p^{sensor_frame} + t EQEND
+/// +/// Where:
+/// EQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

+/// EQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
+/// EQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
+/// +/// Rotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element +/// in the rotation vector is ignored and should be set to 0. +/// +/// When the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked. +/// +/// Example: GNSS antenna lever arm +/// +/// Frame ID: 1 +/// Format: 1 (Euler) +/// Translation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame) +/// Rotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero) +/// +/// +///@{ + +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). + +union mip_aiding_frame_config_command_rotation +{ + mip_vector3f euler; + mip_quatf quaternion; +}; +typedef union mip_aiding_frame_config_command_rotation mip_aiding_frame_config_command_rotation; + +struct mip_aiding_frame_config_command +{ + mip_function_selector function; + uint8_t frame_id; ///< Reference frame number. Limit 4. + mip_aiding_frame_config_command_format format; ///< Format of the transformation. + 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(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_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); + +struct mip_aiding_frame_config_response +{ + uint8_t frame_id; ///< Reference frame number. Limit 4. + mip_aiding_frame_config_command_format format; ///< Format of the transformation. + 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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_aiding_echo_control (0x13,0x1F) Echo Control [C] +/// Controls command response behavior to external aiding commands +/// +///@{ + +typedef uint8_t mip_aiding_echo_control_command_mode; +static const mip_aiding_echo_control_command_mode MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0; ///< Suppresses the usual command ack field for aiding messages. +static const mip_aiding_echo_control_command_mode MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1; ///< Normal ack/nack behavior. +static const mip_aiding_echo_control_command_mode MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2; ///< Echo the data back as a response. + +struct mip_aiding_echo_control_command +{ + mip_function_selector function; + mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. + +}; +typedef struct mip_aiding_echo_control_command mip_aiding_echo_control_command; +void insert_mip_aiding_echo_control_command(struct mip_serializer* serializer, const mip_aiding_echo_control_command* self); +void extract_mip_aiding_echo_control_command(struct mip_serializer* serializer, mip_aiding_echo_control_command* self); + +void insert_mip_aiding_echo_control_command_mode(struct mip_serializer* serializer, const mip_aiding_echo_control_command_mode self); +void extract_mip_aiding_echo_control_command_mode(struct mip_serializer* serializer, mip_aiding_echo_control_command_mode* self); + +struct mip_aiding_echo_control_response +{ + mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. + +}; +typedef struct mip_aiding_echo_control_response mip_aiding_echo_control_response; +void insert_mip_aiding_echo_control_response(struct mip_serializer* serializer, const mip_aiding_echo_control_response* self); +void extract_mip_aiding_echo_control_response(struct mip_serializer* serializer, mip_aiding_echo_control_response* self); + +mip_cmd_result mip_aiding_write_echo_control(struct mip_interface* device, mip_aiding_echo_control_command_mode mode); +mip_cmd_result mip_aiding_read_echo_control(struct mip_interface* device, mip_aiding_echo_control_command_mode* mode_out); +mip_cmd_result mip_aiding_save_echo_control(struct mip_interface* device); +mip_cmd_result mip_aiding_load_echo_control(struct mip_interface* device); +mip_cmd_result mip_aiding_default_echo_control(struct mip_interface* device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@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_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; + +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_pos_ecef_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; +void insert_mip_aiding_pos_ecef_command(struct mip_serializer* serializer, const mip_aiding_pos_ecef_command* self); +void extract_mip_aiding_pos_ecef_command(struct mip_serializer* serializer, mip_aiding_pos_ecef_command* self); + +void insert_mip_aiding_pos_ecef_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_pos_ecef_command_valid_flags self); +void extract_mip_aiding_pos_ecef_command_valid_flags(struct mip_serializer* serializer, mip_aiding_pos_ecef_command_valid_flags* self); + +mip_cmd_result mip_aiding_pos_ecef(struct 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_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_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; + +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). + double latitude; ///< [deg] + 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. + +}; +typedef struct mip_aiding_pos_llh_command mip_aiding_pos_llh_command; +void insert_mip_aiding_pos_llh_command(struct mip_serializer* serializer, const mip_aiding_pos_llh_command* self); +void extract_mip_aiding_pos_llh_command(struct mip_serializer* serializer, mip_aiding_pos_llh_command* self); + +void insert_mip_aiding_pos_llh_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_pos_llh_command_valid_flags self); +void extract_mip_aiding_pos_llh_command_valid_flags(struct mip_serializer* serializer, mip_aiding_pos_llh_command_valid_flags* self); + +mip_cmd_result mip_aiding_pos_llh(struct 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_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [C] +/// Estimated value of the height above ellipsoid. +/// +///@{ + +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). + float height; ///< [m] + float uncertainty; ///< [m] + uint16_t valid_flags; + +}; +typedef struct mip_aiding_height_above_ellipsoid_command mip_aiding_height_above_ellipsoid_command; +void insert_mip_aiding_height_above_ellipsoid_command(struct mip_serializer* serializer, const mip_aiding_height_above_ellipsoid_command* self); +void extract_mip_aiding_height_above_ellipsoid_command(struct mip_serializer* serializer, mip_aiding_height_above_ellipsoid_command* self); + +mip_cmd_result mip_aiding_height_above_ellipsoid(struct 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] +/// 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; + +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_vel_ecef_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; +void insert_mip_aiding_vel_ecef_command(struct mip_serializer* serializer, const mip_aiding_vel_ecef_command* self); +void extract_mip_aiding_vel_ecef_command(struct mip_serializer* serializer, mip_aiding_vel_ecef_command* self); + +void insert_mip_aiding_vel_ecef_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vel_ecef_command_valid_flags self); +void extract_mip_aiding_vel_ecef_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vel_ecef_command_valid_flags* self); + +mip_cmd_result mip_aiding_vel_ecef(struct 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_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_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; + +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_vel_ned_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; +void insert_mip_aiding_vel_ned_command(struct mip_serializer* serializer, const mip_aiding_vel_ned_command* self); +void extract_mip_aiding_vel_ned_command(struct mip_serializer* serializer, mip_aiding_vel_ned_command* self); + +void insert_mip_aiding_vel_ned_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vel_ned_command_valid_flags self); +void extract_mip_aiding_vel_ned_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vel_ned_command_valid_flags* self); + +mip_cmd_result mip_aiding_vel_ned(struct 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_vel_body_frame (0x13,0x2A) Vel Body Frame [C] +/// Estimate of velocity of the vehicle in the frame associated +/// with the given sensor ID, relative to the vehicle frame. +/// +///@{ + +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; + +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_vel_body_frame_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; +void insert_mip_aiding_vel_body_frame_command(struct mip_serializer* serializer, const mip_aiding_vel_body_frame_command* self); +void extract_mip_aiding_vel_body_frame_command(struct mip_serializer* serializer, mip_aiding_vel_body_frame_command* self); + +void insert_mip_aiding_vel_body_frame_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vel_body_frame_command_valid_flags self); +void extract_mip_aiding_vel_body_frame_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vel_body_frame_command_valid_flags* self); + +mip_cmd_result mip_aiding_vel_body_frame(struct 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_heading_true (0x13,0x31) Heading True [C] +/// +///@{ + +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). + 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_heading_true_command mip_aiding_heading_true_command; +void insert_mip_aiding_heading_true_command(struct mip_serializer* serializer, const mip_aiding_heading_true_command* self); +void extract_mip_aiding_heading_true_command(struct mip_serializer* serializer, mip_aiding_heading_true_command* self); + +mip_cmd_result mip_aiding_heading_true(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_aiding_magnetic_field (0x13,0x32) Magnetic Field [C] +/// Estimate of magnetic field in the frame associated with the given sensor ID. +/// +///@{ + +typedef uint16_t mip_aiding_magnetic_field_command_valid_flags; +static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_X = 0x0001; ///< +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; + +struct mip_aiding_magnetic_field_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 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(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_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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_aiding_pressure (0x13,0x33) Pressure [C] +/// Estimated value of air pressure. +/// +///@{ + +struct mip_aiding_pressure_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). + 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(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); + +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); + +///@} +/// + +///@} +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +#ifdef __cplusplus +} // namespace C +} // namespace mip +} // extern "C" +#endif // __cplusplus + diff --git a/src/mip/definitions/commands_aiding.hpp b/src/mip/definitions/commands_aiding.hpp new file mode 100644 index 000000000..3987d1c12 --- /dev/null +++ b/src/mip/definitions/commands_aiding.hpp @@ -0,0 +1,853 @@ +#pragma once + +#include "common.h" +#include "descriptors.h" +#include "../mip_result.h" + +#include +#include +#include + +namespace mip { +class Serializer; + +namespace C { +struct mip_interface; +} // namespace C + +namespace commands_aiding { + +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@{ +///@defgroup aiding_commands_cpp Aiding Commands [CPP] +/// +///@{ + +//////////////////////////////////////////////////////////////////////////////// +// Descriptors +//////////////////////////////////////////////////////////////////////////////// + +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, +}; + +//////////////////////////////////////////////////////////////////////////////// +// Shared Type Definitions +//////////////////////////////////////////////////////////////////////////////// + +struct Time +{ + enum class Timebase : uint8_t + { + INTERNAL_REFERENCE = 1, ///< Timestamp provided is with respect to internal clock. + EXTERNAL_TIME = 2, ///< Timestamp provided is with respect to external clock, synced by PPS source. + TIME_OF_ARRIVAL = 3, ///< Timestamp provided is a fixed latency relative to time of message arrival. + }; + + 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. + +}; +void insert(Serializer& serializer, const Time& self); +void extract(Serializer& serializer, Time& self); + + +//////////////////////////////////////////////////////////////////////////////// +// Mip Fields +//////////////////////////////////////////////////////////////////////////////// + +//////////////////////////////////////////////////////////////////////////////// +///@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) +/// +/// This transform satisfies the following relationship: +/// +/// EQSTART p^{veh} = R p^{sensor_frame} + t EQEND
+/// +/// Where:
+/// EQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

+/// EQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
+/// EQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
+/// +/// Rotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element +/// in the rotation vector is ignored and should be set to 0. +/// +/// When the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked. +/// +/// Example: GNSS antenna lever arm +/// +/// Frame ID: 1 +/// Format: 1 (Euler) +/// Translation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame) +/// Rotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero) +/// +/// +///@{ + +struct FrameConfig +{ + enum class Format : uint8_t + { + EULER = 1, ///< Translation vector followed by euler angles (roll, pitch, yaw). + QUATERNION = 2, ///< Translation vector followed by quaternion (w, x, y, z). + }; + + union Rotation + { + Rotation() {} + Vector3f euler; + Quatf quaternion; + }; + + FunctionSelector function = static_cast(0); + 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. + + 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 + { + return std::make_tuple(frame_id,format,tracking_enabled,translation,rotation); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(frame_id),std::ref(format),std::ref(tracking_enabled),std::ref(translation),std::ref(rotation)); + } + + static FrameConfig create_sld_all(::mip::FunctionSelector function) + { + FrameConfig cmd; + cmd.function = function; + cmd.frame_id = 0; + return cmd; + } + + 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; + 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. + + + auto as_tuple() + { + return std::make_tuple(std::ref(frame_id),std::ref(format),std::ref(tracking_enabled),std::ref(translation),std::ref(rotation)); + } + }; +}; +void insert(Serializer& serializer, const FrameConfig& self); +void extract(Serializer& serializer, FrameConfig& self); + +void insert(Serializer& serializer, const FrameConfig::Response& self); +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); +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); +TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId); +TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_aiding_echo_control (0x13,0x1F) Echo Control [CPP] +/// Controls command response behavior to external aiding commands +/// +///@{ + +struct EchoControl +{ + enum class Mode : uint8_t + { + SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. + STANDARD = 1, ///< Normal ack/nack behavior. + RESPONSE = 2, ///< Echo the data back as a response. + }; + + FunctionSelector function = static_cast(0); + Mode mode = static_cast(0); ///< Controls data echoing. + + 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* 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 + { + return std::make_tuple(mode); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(mode)); + } + + static EchoControl create_sld_all(::mip::FunctionSelector function) + { + EchoControl cmd; + cmd.function = function; + return cmd; + } + + 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_ECHO_CONTROL; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "EchoControl::Response"; + static constexpr const char* DOC_NAME = "Aiding Command Echo Control Response"; + + 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 as_tuple() + { + return std::make_tuple(std::ref(mode)); + } + }; +}; +void insert(Serializer& serializer, const EchoControl& self); +void extract(Serializer& serializer, EchoControl& self); + +void insert(Serializer& serializer, const EchoControl::Response& self); +void extract(Serializer& serializer, EchoControl::Response& self); + +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_pos_ecef (0x13,0x21) Pos Ecef [CPP] +/// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. +/// +///@{ + +struct PosEcef +{ + struct ValidFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + X = 0x0001, ///< + Y = 0x0002, ///< + Z = 0x0004, ///< + ALL = 0x0007, + }; + uint16_t value = NONE; + + ValidFlags() : value(NONE) {} + ValidFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + ValidFlags& operator=(uint16_t val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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; } + }; + + 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. + + 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* DOC_NAME = "ECEF Position"; + + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + + auto as_tuple() const + { + return std::make_tuple(time,frame_id,position,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(position),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const PosEcef& self); +void extract(Serializer& serializer, PosEcef& self); + +TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, PosEcef::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. +/// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. +/// +///@{ + +struct PosLlh +{ + struct ValidFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + LATITUDE = 0x0001, ///< + LONGITUDE = 0x0002, ///< + HEIGHT = 0x0004, ///< + ALL = 0x0007, + }; + uint16_t value = NONE; + + ValidFlags() : value(NONE) {} + ValidFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + ValidFlags& operator=(uint16_t val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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; } + }; + + 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] + double longitude = 0; ///< [deg] + double height = 0; ///< [m] + 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. + + 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* DOC_NAME = "LLH Position"; + + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + + auto as_tuple() const + { + return std::make_tuple(time,frame_id,latitude,longitude,height,uncertainty,valid_flags); + } + + auto as_tuple() + { + 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)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const PosLlh& self); +void extract(Serializer& serializer, PosLlh& self); + +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_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [CPP] +/// Estimated value of the height above ellipsoid. +/// +///@{ + +struct HeightAboveEllipsoid +{ + 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; + + 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 CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "HeightAboveEllipsoid"; + static constexpr const char* DOC_NAME = "Height Above Ellipsoid"; + + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + + auto as_tuple() const + { + return std::make_tuple(time,frame_id,height,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(height),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const HeightAboveEllipsoid& self); +void extract(Serializer& serializer, HeightAboveEllipsoid& self); + +TypedResult heightAboveEllipsoid(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] +/// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. +/// +///@{ + +struct VelEcef +{ + struct ValidFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + X = 0x0001, ///< + Y = 0x0002, ///< + Z = 0x0004, ///< + ALL = 0x0007, + }; + uint16_t value = NONE; + + ValidFlags() : value(NONE) {} + ValidFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + ValidFlags& operator=(uint16_t val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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; } + }; + + 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. + + 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* DOC_NAME = "ECEF Velocity"; + + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + + auto as_tuple() const + { + return std::make_tuple(time,frame_id,velocity,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(velocity),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const VelEcef& self); +void extract(Serializer& serializer, VelEcef& self); + +TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelEcef::ValidFlags validFlags); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@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 VelNed +{ + struct ValidFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + X = 0x0001, ///< + Y = 0x0002, ///< + Z = 0x0004, ///< + ALL = 0x0007, + }; + uint16_t value = NONE; + + ValidFlags() : value(NONE) {} + ValidFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + ValidFlags& operator=(uint16_t val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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; } + }; + + 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. + + 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* DOC_NAME = "NED Velocity"; + + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + + auto as_tuple() const + { + return std::make_tuple(time,frame_id,velocity,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(velocity),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const VelNed& self); +void extract(Serializer& serializer, VelNed& self); + +TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelNed::ValidFlags validFlags); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [CPP] +/// Estimate of velocity of the vehicle in the frame associated +/// with the given sensor ID, relative to the vehicle frame. +/// +///@{ + +struct VelBodyFrame +{ + struct ValidFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + X = 0x0001, ///< + Y = 0x0002, ///< + Z = 0x0004, ///< + ALL = 0x0007, + }; + uint16_t value = NONE; + + ValidFlags() : value(NONE) {} + ValidFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + ValidFlags& operator=(uint16_t val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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; } + }; + + 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. + + 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 CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "VelBodyFrame"; + static constexpr const char* DOC_NAME = "Body Frame Velocity"; + + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + + auto as_tuple() const + { + return std::make_tuple(time,frame_id,velocity,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(velocity),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const VelBodyFrame& self); +void extract(Serializer& serializer, VelBodyFrame& self); + +TypedResult velBodyFrame(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelBodyFrame::ValidFlags validFlags); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_aiding_heading_true (0x13,0x31) Heading True [CPP] +/// +///@{ + +struct HeadingTrue +{ + 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; + + 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* DOC_NAME = "True Heading"; + + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + + auto as_tuple() const + { + return std::make_tuple(time,frame_id,heading,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(heading),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const HeadingTrue& self); +void extract(Serializer& serializer, HeadingTrue& self); + +TypedResult headingTrue(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_aiding_magnetic_field (0x13,0x32) Magnetic Field [CPP] +/// Estimate of magnetic field in the frame associated with the given sensor ID. +/// +///@{ + +struct MagneticField +{ + struct ValidFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + X = 0x0001, ///< + Y = 0x0002, ///< + Z = 0x0004, ///< + ALL = 0x0007, + }; + uint16_t value = NONE; + + ValidFlags() : value(NONE) {} + ValidFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + ValidFlags& operator=(uint16_t val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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; } + }; + + 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. + + 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 + { + return std::make_tuple(time,frame_id,magnetic_field,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(magnetic_field),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const MagneticField& self); +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_aiding_pressure (0x13,0x33) Pressure [CPP] +/// Estimated value of air pressure. +/// +///@{ + +struct Pressure +{ + 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; + + 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 + { + return std::make_tuple(time,frame_id,pressure,uncertainty,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(pressure),std::ref(uncertainty),std::ref(valid_flags)); + } + typedef void Response; +}; +void insert(Serializer& serializer, const Pressure& self); +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); + +///@} +/// + +///@} +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +} // namespace commands_aiding +} // namespace mip + diff --git a/src/mip/definitions/commands_base.c b/src/mip/definitions/commands_base.c index 3868f7619..fd72ea2fa 100644 --- a/src/mip/definitions/commands_base.c +++ b/src/mip/definitions/commands_base.c @@ -130,7 +130,6 @@ mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uin mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(descriptors_out && descriptors_out_count); 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]); @@ -175,7 +174,6 @@ mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, u mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(descriptors_out && descriptors_out_count); 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]); @@ -383,7 +381,7 @@ mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_ assert(mip_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_GPS_TIME_BROADCAST_NEW, 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)mip_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 e89ba54de..35965b4cb 100644 --- a/src/mip/definitions/commands_base.cpp +++ b/src/mip/definitions/commands_base.cpp @@ -81,7 +81,7 @@ void extract(Serializer& serializer, Ping& self) (void)self; } -CmdResult ping(C::mip_interface& device) +TypedResult ping(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PING, NULL, 0); } @@ -96,7 +96,7 @@ void extract(Serializer& serializer, SetIdle& self) (void)self; } -CmdResult setIdle(C::mip_interface& device) +TypedResult setIdle(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_TO_IDLE, NULL, 0); } @@ -122,12 +122,12 @@ void extract(Serializer& serializer, GetDeviceInfo::Response& self) } -CmdResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut) +TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_INFO, NULL, 0, REPLY_DEVICE_INFO, 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 ) { @@ -160,25 +160,22 @@ void insert(Serializer& serializer, const GetDeviceDescriptors::Response& self) } void extract(Serializer& serializer, GetDeviceDescriptors::Response& self) { - assert(self.descriptors || (self.descriptors_count == 0)); - uint8_t descriptorsCountMax = self.descriptors_count; - for(self.descriptors_count = 0; (self.descriptors_count < descriptorsCountMax) && (serializer.remaining() > 0); (self.descriptors_count)++) + 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]); } -CmdResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) +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); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_DESCRIPTORS, NULL, 0, REPLY_DEVICE_DESCRIPTORS, buffer, &responseLength); + 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); - assert(descriptorsOut && descriptorsOutCount); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -209,12 +206,12 @@ void extract(Serializer& serializer, BuiltInTest::Response& self) } -CmdResult builtInTest(C::mip_interface& device, uint32_t* resultOut) +TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_BUILT_IN_TEST, NULL, 0, REPLY_BUILT_IN_TEST, buffer, &responseLength); + 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 ) { @@ -239,7 +236,7 @@ void extract(Serializer& serializer, Resume& self) (void)self; } -CmdResult resume(C::mip_interface& device) +TypedResult resume(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESUME, NULL, 0); } @@ -262,25 +259,22 @@ void insert(Serializer& serializer, const GetExtendedDescriptors::Response& self } void extract(Serializer& serializer, GetExtendedDescriptors::Response& self) { - assert(self.descriptors || (self.descriptors_count == 0)); - uint8_t descriptorsCountMax = self.descriptors_count; - for(self.descriptors_count = 0; (self.descriptors_count < descriptorsCountMax) && (serializer.remaining() > 0); (self.descriptors_count)++) + 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]); } -CmdResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) +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); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_EXTENDED_DESCRIPTORS, NULL, 0, REPLY_GET_EXTENDED_DESCRIPTORS, buffer, &responseLength); + 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); - assert(descriptorsOut && descriptorsOutCount); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -313,12 +307,12 @@ void extract(Serializer& serializer, ContinuousBit::Response& self) } -CmdResult continuousBit(C::mip_interface& device, uint8_t* resultOut) +TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTINUOUS_BIT, NULL, 0, REPLY_CONTINUOUS_BIT, buffer, &responseLength); + 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 ) { @@ -373,7 +367,7 @@ void extract(Serializer& serializer, CommSpeed::Response& self) } -CmdResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t 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)); @@ -387,7 +381,7 @@ CmdResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) +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)); @@ -398,7 +392,7 @@ CmdResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOu assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_COMM_SPEED, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -414,7 +408,7 @@ CmdResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOu } return result; } -CmdResult saveCommSpeed(C::mip_interface& device, uint8_t port) +TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -426,7 +420,7 @@ CmdResult saveCommSpeed(C::mip_interface& device, uint8_t port) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadCommSpeed(C::mip_interface& device, uint8_t port) +TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -438,7 +432,7 @@ CmdResult loadCommSpeed(C::mip_interface& device, uint8_t port) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultCommSpeed(C::mip_interface& device, uint8_t port) +TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -475,7 +469,7 @@ void extract(Serializer& serializer, GpsTimeUpdate& self) } } -CmdResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t 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)); @@ -487,7 +481,7 @@ CmdResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_BROADCAST_NEW, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)mip_serializer_length(&serializer)); } void insert(Serializer& serializer, const SoftReset& self) { @@ -500,7 +494,7 @@ void extract(Serializer& serializer, SoftReset& self) (void)self; } -CmdResult softReset(C::mip_interface& device) +TypedResult softReset(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_RESET, NULL, 0); } diff --git a/src/mip/definitions/commands_base.h b/src/mip/definitions/commands_base.h index 030e04ccb..6d30392c6 100644 --- a/src/mip/definitions/commands_base.h +++ b/src/mip/definitions/commands_base.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -41,9 +42,7 @@ enum MIP_CMD_DESC_BASE_GET_EXTENDED_DESCRIPTORS = 0x07, MIP_CMD_DESC_BASE_CONTINUOUS_BIT = 0x08, MIP_CMD_DESC_BASE_COMM_SPEED = 0x09, - MIP_CMD_DESC_BASE_GPS_TIME_BROADCAST = 0x71, - MIP_CMD_DESC_BASE_GPS_TIME_BROADCAST_NEW = 0x72, - MIP_CMD_DESC_BASE_SYSTEM_TIME = 0x73, + MIP_CMD_DESC_BASE_GPS_TIME_UPDATE = 0x72, MIP_CMD_DESC_BASE_SOFT_RESET = 0x7E, MIP_REPLY_DESC_BASE_DEVICE_INFO = 0x81, @@ -109,6 +108,7 @@ static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_RTCM_F static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_RTK_FAULT = 0x20000000; ///< 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(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); @@ -129,6 +129,7 @@ void extract_mip_commanded_test_bits_gq7(struct mip_serializer* serializer, mip_ ///@{ mip_cmd_result mip_base_ping(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -142,6 +143,7 @@ mip_cmd_result mip_base_ping(struct mip_interface* device); ///@{ mip_cmd_result mip_base_set_idle(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -160,6 +162,7 @@ void insert_mip_base_get_device_info_response(struct mip_serializer* serializer, void extract_mip_base_get_device_info_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -173,8 +176,8 @@ mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_d struct mip_base_get_device_descriptors_response { + uint16_t descriptors[253]; uint8_t descriptors_count; - uint16_t* descriptors; }; typedef struct mip_base_get_device_descriptors_response mip_base_get_device_descriptors_response; @@ -182,6 +185,7 @@ void insert_mip_base_get_device_descriptors_response(struct mip_serializer* seri void extract_mip_base_get_device_descriptors_response(struct mip_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,6 +209,7 @@ void insert_mip_base_built_in_test_response(struct mip_serializer* serializer, c void extract_mip_base_built_in_test_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -216,6 +221,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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -229,8 +235,8 @@ mip_cmd_result mip_base_resume(struct mip_interface* device); struct mip_base_get_extended_descriptors_response { + uint16_t descriptors[253]; uint8_t descriptors_count; - uint16_t* descriptors; }; typedef struct mip_base_get_extended_descriptors_response mip_base_get_extended_descriptors_response; @@ -238,11 +244,12 @@ void insert_mip_base_get_extended_descriptors_response(struct mip_serializer* se void extract_mip_base_get_extended_descriptors_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_base_continuous_bit (0x01,0x08) Continuous Bit [C] -/// Report result of continous built-in test. +/// Report result of continuous built-in test. /// /// This test is non-disruptive but is not as thorough as the commanded BIT. /// @@ -258,6 +265,7 @@ void insert_mip_base_continuous_bit_response(struct mip_serializer* serializer, void extract_mip_base_continuous_bit_response(struct mip_serializer* serializer, mip_base_continuous_bit_response* self); mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* result_out); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -306,10 +314,12 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_base_gps_time_update (0x01,0x72) Gps Time Update [C] +/// 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, /// complete 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. @@ -335,6 +345,7 @@ void insert_mip_base_gps_time_update_command_field_id(struct mip_serializer* ser void extract_mip_base_gps_time_update_command_field_id(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -346,6 +357,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); + ///@} /// diff --git a/src/mip/definitions/commands_base.hpp b/src/mip/definitions/commands_base.hpp index 439a6beff..65a17e7e4 100644 --- a/src/mip/definitions/commands_base.hpp +++ b/src/mip/definitions/commands_base.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -40,9 +41,7 @@ enum CMD_GET_EXTENDED_DESCRIPTORS = 0x07, CMD_CONTINUOUS_BIT = 0x08, CMD_COMM_SPEED = 0x09, - CMD_GPS_TIME_BROADCAST = 0x71, - CMD_GPS_TIME_BROADCAST_NEW = 0x72, - CMD_SYSTEM_TIME = 0x73, + CMD_GPS_TIME_UPDATE = 0x72, CMD_SOFT_RESET = 0x7E, REPLY_DEVICE_INFO = 0x81, @@ -109,6 +108,7 @@ struct CommandedTestBitsGq7 : Bitfield GNSS_RTK_FAULT = 0x20000000, ///< GNSS_SOLUTION_FAULT = 0x40000000, ///< GNSS_GENERAL_FAULT = 0x80000000, ///< + ALL = 0xFFFFFFFF, }; uint32_t value = NONE; @@ -116,9 +116,67 @@ struct CommandedTestBitsGq7 : Bitfield CommandedTestBitsGq7(int val) : value((uint32_t)val) {} operator uint32_t() const { return value; } CommandedTestBitsGq7& operator=(uint32_t val) { value = val; return *this; } - CommandedTestBitsGq7& operator=(int val) { value = val; return *this; } + CommandedTestBitsGq7& operator=(int val) { value = uint32_t(val); return *this; } 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; } }; @@ -138,17 +196,32 @@ struct CommandedTestBitsGq7 : Bitfield struct Ping { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_PING; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; }; void insert(Serializer& serializer, const Ping& self); void extract(Serializer& serializer, Ping& self); -CmdResult ping(C::mip_interface& device); +TypedResult ping(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -163,17 +236,32 @@ CmdResult ping(C::mip_interface& device); struct SetIdle { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_SET_TO_IDLE; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; }; void insert(Serializer& serializer, const SetIdle& self); void extract(Serializer& serializer, SetIdle& self); -CmdResult setIdle(C::mip_interface& device); +TypedResult setIdle(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -184,19 +272,43 @@ CmdResult setIdle(C::mip_interface& device); struct GetDeviceInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GET_DEVICE_INFO; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_DEVICE_INFO; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; BaseDeviceInfo device_info; + + auto as_tuple() + { + return std::make_tuple(std::ref(device_info)); + } }; }; void insert(Serializer& serializer, const GetDeviceInfo& self); @@ -205,7 +317,8 @@ void extract(Serializer& serializer, GetDeviceInfo& self); void insert(Serializer& serializer, const GetDeviceInfo::Response& self); void extract(Serializer& serializer, GetDeviceInfo::Response& self); -CmdResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut); +TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -219,20 +332,44 @@ CmdResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut) struct GetDeviceDescriptors { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GET_DEVICE_DESCRIPTORS; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_DEVICE_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000001; + uint16_t descriptors[253] = {0}; uint8_t descriptors_count = 0; - uint16_t* descriptors = {nullptr}; + + auto as_tuple() + { + return std::make_tuple(std::ref(descriptors),std::ref(descriptors_count)); + } }; }; void insert(Serializer& serializer, const GetDeviceDescriptors& self); @@ -241,7 +378,8 @@ void extract(Serializer& serializer, GetDeviceDescriptors& self); void insert(Serializer& serializer, const GetDeviceDescriptors::Response& self); void extract(Serializer& serializer, GetDeviceDescriptors::Response& self); -CmdResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); +TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -257,19 +395,43 @@ CmdResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOu struct BuiltInTest { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_BUILT_IN_TEST; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_BUILT_IN_TEST; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint32_t result = 0; + + auto as_tuple() + { + return std::make_tuple(std::ref(result)); + } }; }; void insert(Serializer& serializer, const BuiltInTest& self); @@ -278,7 +440,8 @@ void extract(Serializer& serializer, BuiltInTest& self); void insert(Serializer& serializer, const BuiltInTest::Response& self); void extract(Serializer& serializer, BuiltInTest::Response& self); -CmdResult builtInTest(C::mip_interface& device, uint32_t* resultOut); +TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -291,17 +454,32 @@ CmdResult builtInTest(C::mip_interface& device, uint32_t* resultOut); struct Resume { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_RESUME; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; }; void insert(Serializer& serializer, const Resume& self); void extract(Serializer& serializer, Resume& self); -CmdResult resume(C::mip_interface& device); +TypedResult resume(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -315,20 +493,44 @@ CmdResult resume(C::mip_interface& device); struct GetExtendedDescriptors { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GET_EXTENDED_DESCRIPTORS; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_GET_EXTENDED_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000001; + uint16_t descriptors[253] = {0}; uint8_t descriptors_count = 0; - uint16_t* descriptors = {nullptr}; + + auto as_tuple() + { + return std::make_tuple(std::ref(descriptors),std::ref(descriptors_count)); + } }; }; void insert(Serializer& serializer, const GetExtendedDescriptors& self); @@ -337,12 +539,13 @@ void extract(Serializer& serializer, GetExtendedDescriptors& self); void insert(Serializer& serializer, const GetExtendedDescriptors::Response& self); void extract(Serializer& serializer, GetExtendedDescriptors::Response& self); -CmdResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); +TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_base_continuous_bit (0x01,0x08) Continuous Bit [CPP] -/// Report result of continous built-in test. +/// Report result of continuous built-in test. /// /// This test is non-disruptive but is not as thorough as the commanded BIT. /// @@ -350,19 +553,43 @@ CmdResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptors struct ContinuousBit { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_CONTINUOUS_BIT; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_CONTINUOUS_BIT; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(result)); + } }; }; void insert(Serializer& serializer, const ContinuousBit& self); @@ -371,7 +598,8 @@ void extract(Serializer& serializer, ContinuousBit& self); void insert(Serializer& serializer, const ContinuousBit::Response& self); void extract(Serializer& serializer, ContinuousBit::Response& self); -CmdResult continuousBit(C::mip_interface& device, uint8_t* resultOut); +TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -395,28 +623,62 @@ CmdResult continuousBit(C::mip_interface& device, uint8_t* resultOut); struct CommSpeed { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_COMM_SPEED; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - - static const uint32_t ALL_PORTS = 0; + static constexpr const uint32_t ALL_PORTS = 0; 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. + 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 + { + return std::make_tuple(port,baud); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(port),std::ref(baud)); + } + + static CommSpeed create_sld_all(::mip::FunctionSelector function) + { + CommSpeed cmd; + cmd.function = function; + cmd.port = 0; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_COMM_SPEED; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(port),std::ref(baud)); + } }; }; void insert(Serializer& serializer, const CommSpeed& self); @@ -425,15 +687,17 @@ void extract(Serializer& serializer, CommSpeed& self); void insert(Serializer& serializer, const CommSpeed::Response& self); void extract(Serializer& serializer, CommSpeed::Response& self); -CmdResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud); -CmdResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut); -CmdResult saveCommSpeed(C::mip_interface& device, uint8_t port); -CmdResult loadCommSpeed(C::mip_interface& device, uint8_t port); -CmdResult defaultCommSpeed(C::mip_interface& device, uint8_t port); +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); +TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port); +TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_base_gps_time_update (0x01,0x72) Gps Time Update [CPP] +/// 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, /// complete 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. @@ -442,15 +706,6 @@ CmdResult defaultCommSpeed(C::mip_interface& device, uint8_t port); struct GpsTimeUpdate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GPS_TIME_BROADCAST_NEW; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = false; - static const bool HAS_SAVE_FUNCTION = false; - static const bool HAS_LOAD_FUNCTION = false; - static const bool HAS_RESET_FUNCTION = false; - enum class FieldId : uint8_t { WEEK_NUMBER = 1, ///< Week number. @@ -461,11 +716,44 @@ struct GpsTimeUpdate 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. + 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 + { + return std::make_tuple(field_id,value); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(field_id),std::ref(value)); + } + + static GpsTimeUpdate create_sld_all(::mip::FunctionSelector function) + { + GpsTimeUpdate cmd; + cmd.function = function; + return cmd; + } + + typedef void Response; }; void insert(Serializer& serializer, const GpsTimeUpdate& self); void extract(Serializer& serializer, GpsTimeUpdate& self); -CmdResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value); +TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -478,17 +766,32 @@ CmdResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fi struct SoftReset { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_SOFT_RESET; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; }; void insert(Serializer& serializer, const SoftReset& self); void extract(Serializer& serializer, SoftReset& self); -CmdResult softReset(C::mip_interface& device); +TypedResult softReset(C::mip_interface& device); + ///@} /// diff --git a/src/mip/definitions/commands_filter.c b/src/mip/definitions/commands_filter.c index 4edc45da0..7cc6aed8f 100644 --- a/src/mip/definitions/commands_filter.c +++ b/src/mip/definitions/commands_filter.c @@ -33,11 +33,22 @@ void extract_mip_filter_reference_frame(struct mip_serializer* serializer, mip_f *self = tmp; } -void insert_mip_filter_mag_declination_source(struct mip_serializer* serializer, const mip_filter_mag_declination_source self) +void insert_mip_filter_mag_param_source(struct mip_serializer* serializer, const mip_filter_mag_param_source self) { insert_u8(serializer, (uint8_t)(self)); } -void extract_mip_filter_mag_declination_source(struct mip_serializer* serializer, mip_filter_mag_declination_source* 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); + *self = tmp; +} + +void insert_mip_filter_adaptive_measurement(struct mip_serializer* serializer, const mip_filter_adaptive_measurement self) +{ + 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); @@ -485,6 +496,125 @@ 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)mip_serializer_length(&serializer)); } +void insert_mip_filter_vehicle_dynamics_mode_command(mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, self->mode); + + } +} +void extract_mip_filter_vehicle_dynamics_mode_command(mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, &self->mode); + + } +} + +void insert_mip_filter_vehicle_dynamics_mode_response(mip_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) +{ + 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) +{ + 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); + *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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(&serializer, mode); + + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(mode_out); + extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(&deserializer, mode_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_vehicle_dynamics_mode(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1425,39 +1555,2188 @@ 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)mip_serializer_length(&serializer)); } -void insert_mip_filter_altitude_aiding_command(mip_serializer* serializer, const mip_filter_altitude_aiding_command* self) +void insert_mip_filter_accel_noise_command(mip_serializer* serializer, const mip_filter_accel_noise_command* self) { insert_mip_function_selector(serializer, self->function); if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->aiding_selector); + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); } } -void extract_mip_filter_altitude_aiding_command(mip_serializer* serializer, mip_filter_altitude_aiding_command* self) +void extract_mip_filter_accel_noise_command(mip_serializer* serializer, mip_filter_accel_noise_command* self) { extract_mip_function_selector(serializer, &self->function); if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->aiding_selector); + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->noise[i]); } } -void insert_mip_filter_altitude_aiding_response(mip_serializer* serializer, const mip_filter_altitude_aiding_response* self) +void insert_mip_filter_accel_noise_response(mip_serializer* serializer, const mip_filter_accel_noise_response* self) { - insert_u8(serializer, self->aiding_selector); + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); } -void extract_mip_filter_altitude_aiding_response(mip_serializer* serializer, mip_filter_altitude_aiding_response* self) +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]); + +} + +mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const float* noise) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_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++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(noise_out || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract_float(&deserializer, &noise_out[i]); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_accel_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_gyro_noise_command(mip_serializer* serializer, const mip_filter_gyro_noise_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); + + } +} +void extract_mip_filter_gyro_noise_command(mip_serializer* serializer, mip_filter_gyro_noise_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->noise[i]); + + } +} + +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]); + +} +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]); + +} + +mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const float* noise) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_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++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(noise_out || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract_float(&deserializer, &noise_out[i]); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_gyro_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_accel_bias_model_command(mip_serializer* serializer, const mip_filter_accel_bias_model_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->beta[i]); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); + + } +} +void extract_mip_filter_accel_bias_model_command(mip_serializer* serializer, mip_filter_accel_bias_model_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->beta[i]); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->noise[i]); + + } +} + +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]); + + for(unsigned int i=0; i < 3; i++) + 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]); + + for(unsigned int i=0; i < 3; i++) + 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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + assert(beta || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, beta[i]); + + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(beta_out || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + 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]); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_accel_bias_model(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_gyro_bias_model_command(mip_serializer* serializer, const mip_filter_gyro_bias_model_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->beta[i]); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); + + } +} +void extract_mip_filter_gyro_bias_model_command(mip_serializer* serializer, mip_filter_gyro_bias_model_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->beta[i]); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->noise[i]); + + } +} + +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]); + + for(unsigned int i=0; i < 3; i++) + 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]); + + for(unsigned int i=0; i < 3; i++) + 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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + assert(beta || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, beta[i]); + + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(beta_out || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + 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]); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_gyro_bias_model(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_altitude_aiding_command(mip_serializer* serializer, const mip_filter_altitude_aiding_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_mip_filter_altitude_aiding_command_aiding_selector(serializer, self->selector); + + } +} +void extract_mip_filter_altitude_aiding_command(mip_serializer* serializer, mip_filter_altitude_aiding_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_mip_filter_altitude_aiding_command_aiding_selector(serializer, &self->selector); + + } +} + +void insert_mip_filter_altitude_aiding_response(mip_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) +{ + 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) +{ + 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); + *self = tmp; +} + +mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_filter_altitude_aiding_command_aiding_selector(&serializer, selector); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(selector_out); + extract_mip_filter_altitude_aiding_command_aiding_selector(&deserializer, selector_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_pitch_roll_aiding_command(mip_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, self->source); + + } +} +void extract_mip_filter_pitch_roll_aiding_command(mip_serializer* serializer, mip_filter_pitch_roll_aiding_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, &self->source); + + } +} + +void insert_mip_filter_pitch_roll_aiding_response(mip_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) +{ + 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) +{ + 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); + *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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_filter_pitch_roll_aiding_command_aiding_source(&serializer, source); + + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(source_out); + extract_mip_filter_pitch_roll_aiding_command_aiding_source(&deserializer, source_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_pitch_roll_aiding(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_auto_zupt_command(mip_serializer* serializer, const mip_filter_auto_zupt_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_u8(serializer, self->enable); + + insert_float(serializer, self->threshold); + + } +} +void extract_mip_filter_auto_zupt_command(mip_serializer* serializer, mip_filter_auto_zupt_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_u8(serializer, &self->enable); + + 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); + +} +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); + +} + +mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t enable, float threshold) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_u8(&serializer, enable); + + insert_float(&serializer, threshold); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(enable_out); + extract_u8(&deserializer, enable_out); + + assert(threshold_out); + extract_float(&deserializer, threshold_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, const mip_filter_auto_angular_zupt_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_u8(serializer, self->enable); + + insert_float(serializer, self->threshold); + + } +} +void extract_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, mip_filter_auto_angular_zupt_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_u8(serializer, &self->enable); + + 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); + +} +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); + +} + +mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, uint8_t enable, float threshold) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_u8(&serializer, enable); + + insert_float(&serializer, threshold); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(enable_out); + extract_u8(&deserializer, enable_out); + + assert(threshold_out); + extract_float(&deserializer, threshold_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +mip_cmd_result mip_filter_commanded_zupt(struct 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) +{ + 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) +{ + 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) +{ + extract_mip_function_selector(serializer, &self->function); + +} + +mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +void insert_mip_filter_gravity_noise_command(mip_serializer* serializer, const mip_filter_gravity_noise_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); + + } +} +void extract_mip_filter_gravity_noise_command(mip_serializer* serializer, mip_filter_gravity_noise_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->noise[i]); + + } +} + +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]); + +} +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]); + +} + +mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, const float* noise) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_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++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(noise_out || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract_float(&deserializer, &noise_out[i]); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_gravity_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_pressure_altitude_noise_command(mip_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_float(serializer, self->noise); + + } +} +void extract_mip_filter_pressure_altitude_noise_command(mip_serializer* serializer, mip_filter_pressure_altitude_noise_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + 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); + +} +void extract_mip_filter_pressure_altitude_noise_response(mip_serializer* serializer, mip_filter_pressure_altitude_noise_response* self) +{ + extract_float(serializer, &self->noise); + +} + +mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* device, float noise) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_float(&serializer, noise); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* device, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(noise_out); + extract_float(&deserializer, noise_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_pressure_altitude_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_hard_iron_offset_noise_command(mip_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); + + } +} +void extract_mip_filter_hard_iron_offset_noise_command(mip_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->noise[i]); + + } +} + +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]); + +} +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]); + +} + +mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* device, const float* noise) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_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++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* device, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(noise_out || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract_float(&deserializer, &noise_out[i]); + + if( mip_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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 9; i++) + insert_float(serializer, self->noise[i]); + + } +} +void extract_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 9; i++) + extract_float(serializer, &self->noise[i]); + + } +} + +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]); + +} +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]); + +} + +mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* device, const float* noise) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + assert(noise || (9 == 0)); + for(unsigned int i=0; i < 9; i++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* device, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(noise_out || (9 == 0)); + for(unsigned int i=0; i < 9; i++) + extract_float(&deserializer, &noise_out[i]); + + if( mip_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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_mag_noise_command(mip_serializer* serializer, const mip_filter_mag_noise_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->noise[i]); + + } +} +void extract_mip_filter_mag_noise_command(mip_serializer* serializer, mip_filter_mag_noise_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->noise[i]); + + } +} + +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]); + +} +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]); + +} + +mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const float* noise) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_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++) + insert_float(&serializer, noise[i]); + + assert(mip_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)); +} +mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* noise_out) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(noise_out || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract_float(&deserializer, &noise_out[i]); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_mag_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_inclination_source_command(mip_serializer* serializer, const mip_filter_inclination_source_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_mip_filter_mag_param_source(serializer, self->source); + + insert_float(serializer, self->inclination); + + } +} +void extract_mip_filter_inclination_source_command(mip_serializer* serializer, mip_filter_inclination_source_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_mip_filter_mag_param_source(serializer, &self->source); + + extract_float(serializer, &self->inclination); + + } +} + +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); + +} +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); + +} + +mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, mip_filter_mag_param_source source, float inclination) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_filter_mag_param_source(&serializer, source); + + insert_float(&serializer, inclination); + + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(source_out); + extract_mip_filter_mag_param_source(&deserializer, source_out); + + assert(inclination_out); + extract_float(&deserializer, inclination_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_inclination_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_magnetic_declination_source_command(mip_serializer* serializer, const mip_filter_magnetic_declination_source_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_mip_filter_mag_param_source(serializer, self->source); + + insert_float(serializer, self->declination); + + } +} +void extract_mip_filter_magnetic_declination_source_command(mip_serializer* serializer, mip_filter_magnetic_declination_source_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_mip_filter_mag_param_source(serializer, &self->source); + + extract_float(serializer, &self->declination); + + } +} + +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); + +} +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); + +} + +mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source source, float declination) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_filter_mag_param_source(&serializer, source); + + insert_float(&serializer, declination); + + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(source_out); + extract_mip_filter_mag_param_source(&deserializer, source_out); + + assert(declination_out); + extract_float(&deserializer, declination_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_mag_field_magnitude_source_command(mip_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + insert_mip_filter_mag_param_source(serializer, self->source); + + insert_float(serializer, self->magnitude); + + } +} +void extract_mip_filter_mag_field_magnitude_source_command(mip_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + if( self->function == MIP_FUNCTION_WRITE ) + { + extract_mip_filter_mag_param_source(serializer, &self->source); + + extract_float(serializer, &self->magnitude); + + } +} + +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); + +} +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); + +} + +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_mip_filter_mag_param_source(&serializer, source); + + insert_float(&serializer, magnitude); + + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(source_out); + extract_mip_filter_mag_param_source(&deserializer, source_out); + + assert(magnitude_out); + extract_float(&deserializer, magnitude_out); + + if( mip_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_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_reference_position_command(mip_serializer* serializer, const mip_filter_reference_position_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + 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); + + } +} +void extract_mip_filter_reference_position_command(mip_serializer* serializer, mip_filter_reference_position_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + 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); + + } +} + +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); + +} +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); + +} + +mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, bool enable, double latitude, double longitude, double altitude) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + insert_bool(&serializer, enable); + + insert_double(&serializer, latitude); + + insert_double(&serializer, longitude); + + insert_double(&serializer, altitude); + + assert(mip_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)); +} +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; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + assert(mip_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); + + if( result == MIP_ACK_OK ) + { + mip_serializer deserializer; + mip_serializer_init_insertion(&deserializer, buffer, responseLength); + + assert(enable_out); + extract_bool(&deserializer, enable_out); + + assert(latitude_out); + extract_double(&deserializer, latitude_out); + + assert(longitude_out); + extract_double(&deserializer, longitude_out); + + assert(altitude_out); + extract_double(&deserializer, altitude_out); + + if( mip_serializer_remaining(&deserializer) != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +mip_cmd_result mip_filter_save_reference_position(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + assert(mip_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)); +} +mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + assert(mip_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)); +} +mip_cmd_result mip_filter_default_reference_position(struct mip_interface* device) +{ + mip_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + assert(mip_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)); +} +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self) +{ + insert_mip_function_selector(serializer, self->function); + + 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); + + } +} +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self) +{ + extract_mip_function_selector(serializer, &self->function); + + 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); + + } +} + +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); + +} +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self) { - extract_u8(serializer, &self->aiding_selector); + 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); } -mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, uint8_t aiding_selector) +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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1465,13 +3744,25 @@ mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, ui insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - insert_u8(&serializer, aiding_selector); + insert_mip_filter_adaptive_measurement(&serializer, adaptive_measurement); + + 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)); - 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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, uint8_t* aiding_selector_out) +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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1482,22 +3773,40 @@ mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, uin assert(mip_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_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); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(aiding_selector_out); - extract_u8(&deserializer, aiding_selector_out); + assert(adaptive_measurement_out); + extract_mip_filter_adaptive_measurement(&deserializer, adaptive_measurement_out); + + assert(frequency_out); + extract_float(&deserializer, frequency_out); + + assert(low_limit_out); + extract_float(&deserializer, low_limit_out); + + assert(high_limit_out); + extract_float(&deserializer, high_limit_out); + + assert(low_limit_uncertainty_out); + extract_float(&deserializer, low_limit_uncertainty_out); + + assert(high_limit_uncertainty_out); + extract_float(&deserializer, high_limit_uncertainty_out); + + assert(minimum_uncertainty_out); + extract_float(&deserializer, minimum_uncertainty_out); if( mip_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_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1507,9 +3816,9 @@ mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device) assert(mip_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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1519,9 +3828,9 @@ mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) assert(mip_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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1531,49 +3840,89 @@ mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) assert(mip_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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -void insert_mip_filter_auto_zupt_command(mip_serializer* serializer, const mip_filter_auto_zupt_command* self) +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self) { insert_mip_function_selector(serializer, self->function); if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); + insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - insert_float(serializer, self->threshold); + 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); } } -void extract_mip_filter_auto_zupt_command(mip_serializer* serializer, mip_filter_auto_zupt_command* self) +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self) { extract_mip_function_selector(serializer, &self->function); if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); + extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - extract_float(serializer, &self->threshold); + 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); } } -void insert_mip_filter_auto_zupt_response(mip_serializer* serializer, const mip_filter_auto_zupt_response* self) +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self) { - insert_u8(serializer, self->enable); + insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - insert_float(serializer, self->threshold); + 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); } -void extract_mip_filter_auto_zupt_response(mip_serializer* serializer, mip_filter_auto_zupt_response* self) +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self) { - extract_u8(serializer, &self->enable); + extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - extract_float(serializer, &self->threshold); + 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); } -mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t enable, float threshold) +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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1581,15 +3930,25 @@ mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - insert_u8(&serializer, enable); + insert_mip_filter_adaptive_measurement(&serializer, adaptive_measurement); - insert_float(&serializer, threshold); + 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)); - 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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_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_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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1600,25 +3959,40 @@ mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* assert(mip_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_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); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(enable_out); - extract_u8(&deserializer, enable_out); + assert(adaptive_measurement_out); + extract_mip_filter_adaptive_measurement(&deserializer, adaptive_measurement_out); - assert(threshold_out); - extract_float(&deserializer, threshold_out); + assert(frequency_out); + extract_float(&deserializer, frequency_out); + + assert(low_limit_out); + extract_float(&deserializer, low_limit_out); + + assert(high_limit_out); + extract_float(&deserializer, high_limit_out); + + assert(low_limit_uncertainty_out); + extract_float(&deserializer, low_limit_uncertainty_out); + + assert(high_limit_uncertainty_out); + extract_float(&deserializer, high_limit_uncertainty_out); + + assert(minimum_uncertainty_out); + extract_float(&deserializer, minimum_uncertainty_out); if( mip_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_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1628,9 +4002,9 @@ mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device) assert(mip_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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1640,9 +4014,9 @@ mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) assert(mip_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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1652,49 +4026,73 @@ mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) assert(mip_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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_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_mag_dip_angle_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) { insert_mip_function_selector(serializer, self->function); if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); + insert_bool(serializer, self->enable); - insert_float(serializer, self->threshold); + insert_float(serializer, self->frequency); + + insert_float(serializer, self->high_limit); + + insert_float(serializer, self->high_limit_uncertainty); + + insert_float(serializer, self->minimum_uncertainty); } } -void extract_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, mip_filter_auto_angular_zupt_command* self) +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) { extract_mip_function_selector(serializer, &self->function); if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); + extract_bool(serializer, &self->enable); - extract_float(serializer, &self->threshold); + extract_float(serializer, &self->frequency); + + extract_float(serializer, &self->high_limit); + + extract_float(serializer, &self->high_limit_uncertainty); + + extract_float(serializer, &self->minimum_uncertainty); } } -void insert_mip_filter_auto_angular_zupt_response(mip_serializer* serializer, const mip_filter_auto_angular_zupt_response* self) +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_u8(serializer, self->enable); + insert_bool(serializer, self->enable); - insert_float(serializer, self->threshold); + insert_float(serializer, self->frequency); + + insert_float(serializer, self->high_limit); + + insert_float(serializer, self->high_limit_uncertainty); + + insert_float(serializer, self->minimum_uncertainty); } -void extract_mip_filter_auto_angular_zupt_response(mip_serializer* serializer, mip_filter_auto_angular_zupt_response* self) +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_u8(serializer, &self->enable); + extract_bool(serializer, &self->enable); - extract_float(serializer, &self->threshold); + extract_float(serializer, &self->frequency); + + extract_float(serializer, &self->high_limit); + + extract_float(serializer, &self->high_limit_uncertainty); + + extract_float(serializer, &self->minimum_uncertainty); } -mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, uint8_t enable, float threshold) +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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1702,15 +4100,21 @@ mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - insert_u8(&serializer, enable); + insert_bool(&serializer, enable); - insert_float(&serializer, threshold); + 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)); - 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_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_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_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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1721,7 +4125,7 @@ mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, u assert(mip_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_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); if( result == MIP_ACK_OK ) { @@ -1729,17 +4133,26 @@ 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); + extract_bool(&deserializer, enable_out); - assert(threshold_out); - extract_float(&deserializer, threshold_out); + assert(frequency_out); + extract_float(&deserializer, frequency_out); + + assert(high_limit_out); + extract_float(&deserializer, high_limit_out); + + assert(high_limit_uncertainty_out); + extract_float(&deserializer, high_limit_uncertainty_out); + + assert(minimum_uncertainty_out); + extract_float(&deserializer, minimum_uncertainty_out); if( mip_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_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1749,9 +4162,9 @@ mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device) assert(mip_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_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1761,9 +4174,9 @@ mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) assert(mip_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_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1773,15 +4186,7 @@ mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device assert(mip_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)); -} -mip_cmd_result mip_filter_commanded_zupt(struct 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) -{ - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_COMMANDED_ANGULAR_ZUPT, NULL, 0); + 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)); } void insert_mip_filter_aiding_measurement_enable_command(mip_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self) { @@ -3357,127 +5762,6 @@ 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)mip_serializer_length(&serializer)); } -void insert_mip_filter_magnetic_declination_source_command(mip_serializer* serializer, const mip_filter_magnetic_declination_source_command* self) -{ - insert_mip_function_selector(serializer, self->function); - - if( self->function == MIP_FUNCTION_WRITE ) - { - insert_mip_filter_mag_declination_source(serializer, self->source); - - insert_float(serializer, self->declination); - - } -} -void extract_mip_filter_magnetic_declination_source_command(mip_serializer* serializer, mip_filter_magnetic_declination_source_command* self) -{ - extract_mip_function_selector(serializer, &self->function); - - if( self->function == MIP_FUNCTION_WRITE ) - { - extract_mip_filter_mag_declination_source(serializer, &self->source); - - extract_float(serializer, &self->declination); - - } -} - -void insert_mip_filter_magnetic_declination_source_response(mip_serializer* serializer, const mip_filter_magnetic_declination_source_response* self) -{ - insert_mip_filter_mag_declination_source(serializer, self->source); - - 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_declination_source(serializer, &self->source); - - extract_float(serializer, &self->declination); - -} - -mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_declination_source source, float declination) -{ - mip_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_mip_filter_mag_declination_source(&serializer, source); - - insert_float(&serializer, declination); - - assert(mip_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)); -} -mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_declination_source* source_out, float* declination_out) -{ - mip_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - - assert(mip_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); - - if( result == MIP_ACK_OK ) - { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - assert(source_out); - extract_mip_filter_mag_declination_source(&deserializer, source_out); - - assert(declination_out); - extract_float(&deserializer, declination_out); - - if( mip_serializer_remaining(&deserializer) != 0 ) - result = MIP_STATUS_ERROR; - } - return result; -} -mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* device) -{ - mip_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - - assert(mip_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)); -} -mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* device) -{ - mip_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - - assert(mip_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)); -} -mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interface* device) -{ - mip_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - - assert(mip_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)); -} void insert_mip_filter_set_initial_heading_command(mip_serializer* serializer, const mip_filter_set_initial_heading_command* self) { insert_float(serializer, self->heading); diff --git a/src/mip/definitions/commands_filter.cpp b/src/mip/definitions/commands_filter.cpp index 12e176284..7792142bf 100644 --- a/src/mip/definitions/commands_filter.cpp +++ b/src/mip/definitions/commands_filter.cpp @@ -40,7 +40,7 @@ void extract(Serializer& serializer, Reset& self) (void)self; } -CmdResult reset(C::mip_interface& device) +TypedResult reset(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESET_FILTER, NULL, 0); } @@ -63,7 +63,7 @@ void extract(Serializer& serializer, SetInitialAttitude& self) } -CmdResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading) +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)); @@ -110,7 +110,7 @@ void extract(Serializer& serializer, EstimationControl::Response& self) } -CmdResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) +TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -122,7 +122,7 @@ CmdResult writeEstimationControl(C::mip_interface& device, EstimationControl::En return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) +TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -131,7 +131,7 @@ CmdResult readEstimationControl(C::mip_interface& device, EstimationControl::Ena assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -145,7 +145,7 @@ CmdResult readEstimationControl(C::mip_interface& device, EstimationControl::Ena } return result; } -CmdResult saveEstimationControl(C::mip_interface& device) +TypedResult saveEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -155,7 +155,7 @@ CmdResult saveEstimationControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadEstimationControl(C::mip_interface& device) +TypedResult loadEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -165,7 +165,7 @@ CmdResult loadEstimationControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultEstimationControl(C::mip_interface& device) +TypedResult defaultEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -220,7 +220,7 @@ void extract(Serializer& serializer, ExternalGnssUpdate& self) } -CmdResult 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) +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)); @@ -270,7 +270,7 @@ void extract(Serializer& serializer, ExternalHeadingUpdate& self) } -CmdResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type) +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)); @@ -312,7 +312,7 @@ void extract(Serializer& serializer, ExternalHeadingUpdateWithTime& self) } -CmdResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type) +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)); @@ -363,7 +363,7 @@ void extract(Serializer& serializer, TareOrientation::Response& self) } -CmdResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) +TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -375,7 +375,7 @@ CmdResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTar return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) +TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -384,7 +384,7 @@ CmdResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTare assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_TARE_ORIENTATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -398,7 +398,7 @@ CmdResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTare } return result; } -CmdResult saveTareOrientation(C::mip_interface& device) +TypedResult saveTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -408,7 +408,7 @@ CmdResult saveTareOrientation(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadTareOrientation(C::mip_interface& device) +TypedResult loadTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -418,7 +418,7 @@ CmdResult loadTareOrientation(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultTareOrientation(C::mip_interface& device) +TypedResult defaultTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -428,6 +428,103 @@ CmdResult defaultTareOrientation(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } +void insert(Serializer& serializer, const VehicleDynamicsMode& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.mode); + + } +} +void extract(Serializer& serializer, VehicleDynamicsMode& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.mode); + + } +} + +void insert(Serializer& serializer, const VehicleDynamicsMode::Response& self) +{ + insert(serializer, self.mode); + +} +void extract(Serializer& serializer, VehicleDynamicsMode::Response& self) +{ + extract(serializer, self.mode); + +} + +TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(modeOut); + extract(deserializer, *modeOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveVehicleDynamicsMode(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadVehicleDynamicsMode(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} void insert(Serializer& serializer, const SensorToVehicleRotationEuler& self) { insert(serializer, self.function); @@ -476,7 +573,7 @@ void extract(Serializer& serializer, SensorToVehicleRotationEuler::Response& sel } -CmdResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw) +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)); @@ -492,7 +589,7 @@ CmdResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) +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)); @@ -501,7 +598,7 @@ CmdResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* roll assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -521,7 +618,7 @@ CmdResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* roll } return result; } -CmdResult saveSensorToVehicleRotationEuler(C::mip_interface& device) +TypedResult saveSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -531,7 +628,7 @@ CmdResult saveSensorToVehicleRotationEuler(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensorToVehicleRotationEuler(C::mip_interface& device) +TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -541,7 +638,7 @@ CmdResult loadSensorToVehicleRotationEuler(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) +TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -587,7 +684,7 @@ void extract(Serializer& serializer, SensorToVehicleRotationDcm::Response& self) } -CmdResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) +TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -601,7 +698,7 @@ CmdResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) +TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -610,7 +707,7 @@ CmdResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -625,7 +722,7 @@ CmdResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut } return result; } -CmdResult saveSensorToVehicleRotationDcm(C::mip_interface& device) +TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -635,7 +732,7 @@ CmdResult saveSensorToVehicleRotationDcm(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensorToVehicleRotationDcm(C::mip_interface& device) +TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -645,7 +742,7 @@ CmdResult loadSensorToVehicleRotationDcm(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) +TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -691,7 +788,7 @@ void extract(Serializer& serializer, SensorToVehicleRotationQuaternion::Response } -CmdResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) +TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -705,7 +802,7 @@ CmdResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) +TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -714,7 +811,7 @@ CmdResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -729,7 +826,7 @@ CmdResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* } return result; } -CmdResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) +TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -739,7 +836,7 @@ CmdResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) +TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -749,7 +846,7 @@ CmdResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) +TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -795,7 +892,7 @@ void extract(Serializer& serializer, SensorToVehicleOffset::Response& self) } -CmdResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) +TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -809,7 +906,7 @@ CmdResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offs return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) +TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -818,7 +915,7 @@ CmdResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -833,7 +930,7 @@ CmdResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) } return result; } -CmdResult saveSensorToVehicleOffset(C::mip_interface& device) +TypedResult saveSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -843,7 +940,7 @@ CmdResult saveSensorToVehicleOffset(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSensorToVehicleOffset(C::mip_interface& device) +TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -853,7 +950,7 @@ CmdResult loadSensorToVehicleOffset(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSensorToVehicleOffset(C::mip_interface& device) +TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -899,7 +996,7 @@ void extract(Serializer& serializer, AntennaOffset::Response& self) } -CmdResult writeAntennaOffset(C::mip_interface& device, const float* offset) +TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -913,7 +1010,7 @@ CmdResult writeAntennaOffset(C::mip_interface& device, const float* offset) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAntennaOffset(C::mip_interface& device, float* offsetOut) +TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -922,7 +1019,7 @@ CmdResult readAntennaOffset(C::mip_interface& device, float* offsetOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -937,7 +1034,7 @@ CmdResult readAntennaOffset(C::mip_interface& device, float* offsetOut) } return result; } -CmdResult saveAntennaOffset(C::mip_interface& device) +TypedResult saveAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -947,7 +1044,7 @@ CmdResult saveAntennaOffset(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAntennaOffset(C::mip_interface& device) +TypedResult loadAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -957,7 +1054,7 @@ CmdResult loadAntennaOffset(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAntennaOffset(C::mip_interface& device) +TypedResult defaultAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -999,7 +1096,7 @@ void extract(Serializer& serializer, GnssSource::Response& self) } -CmdResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) +TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1011,7 +1108,7 @@ CmdResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) +TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1020,7 +1117,7 @@ CmdResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1034,7 +1131,7 @@ CmdResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut } return result; } -CmdResult saveGnssSource(C::mip_interface& device) +TypedResult saveGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1044,7 +1141,7 @@ CmdResult saveGnssSource(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadGnssSource(C::mip_interface& device) +TypedResult loadGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1054,7 +1151,7 @@ CmdResult loadGnssSource(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultGnssSource(C::mip_interface& device) +TypedResult defaultGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1096,7 +1193,7 @@ void extract(Serializer& serializer, HeadingSource::Response& self) } -CmdResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) +TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1108,7 +1205,7 @@ CmdResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source sou return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) +TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1117,7 +1214,7 @@ CmdResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sou assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1131,7 +1228,7 @@ CmdResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sou } return result; } -CmdResult saveHeadingSource(C::mip_interface& device) +TypedResult saveHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1141,7 +1238,7 @@ CmdResult saveHeadingSource(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadHeadingSource(C::mip_interface& device) +TypedResult loadHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1151,7 +1248,7 @@ CmdResult loadHeadingSource(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultHeadingSource(C::mip_interface& device) +TypedResult defaultHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1193,7 +1290,7 @@ void extract(Serializer& serializer, AutoInitControl::Response& self) } -CmdResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) +TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1205,7 +1302,7 @@ CmdResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) +TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1214,7 +1311,7 @@ CmdResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1228,7 +1325,7 @@ CmdResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) } return result; } -CmdResult saveAutoInitControl(C::mip_interface& device) +TypedResult saveAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1238,7 +1335,7 @@ CmdResult saveAutoInitControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAutoInitControl(C::mip_interface& device) +TypedResult loadAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1248,7 +1345,7 @@ CmdResult loadAutoInitControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAutoInitControl(C::mip_interface& device) +TypedResult defaultAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1258,51 +1355,2021 @@ CmdResult defaultAutoInitControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -void insert(Serializer& serializer, const AltitudeAiding& self) +void insert(Serializer& serializer, const AccelNoise& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.noise[i]); + + } +} +void extract(Serializer& serializer, AccelNoise& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.noise[i]); + + } +} + +void insert(Serializer& 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) +{ + 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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_ACCEL_NOISE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(noiseOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveAccelNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadAccelNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultAccelNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const GyroNoise& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.noise[i]); + + } +} +void extract(Serializer& serializer, GyroNoise& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.noise[i]); + + } +} + +void insert(Serializer& 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) +{ + 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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_GYRO_NOISE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(noiseOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveGyroNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadGyroNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultGyroNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const AccelBiasModel& self) { insert(serializer, self.function); if( self.function == FunctionSelector::WRITE ) { - insert(serializer, self.aiding_selector); + 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(Serializer& serializer, AccelBiasModel& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + 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]); + + } +} + +void insert(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(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(beta || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, beta[i]); + + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(betaOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, betaOut[i]); + + assert(noiseOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveAccelBiasModel(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadAccelBiasModel(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultAccelBiasModel(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const GyroBiasModel& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + 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(Serializer& serializer, GyroBiasModel& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + 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]); + + } +} + +void insert(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(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(beta || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, beta[i]); + + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(betaOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, betaOut[i]); + + assert(noiseOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveGyroBiasModel(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadGyroBiasModel(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultGyroBiasModel(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const AltitudeAiding& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.selector); + + } +} +void extract(Serializer& serializer, AltitudeAiding& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.selector); + + } +} + +void insert(Serializer& serializer, const AltitudeAiding::Response& self) +{ + insert(serializer, self.selector); + +} +void extract(Serializer& serializer, AltitudeAiding::Response& self) +{ + extract(serializer, self.selector); + +} + +TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(selectorOut); + extract(deserializer, *selectorOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveAltitudeAiding(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadAltitudeAiding(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultAltitudeAiding(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const PitchRollAiding& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.source); + + } +} +void extract(Serializer& serializer, PitchRollAiding& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.source); + + } +} + +void insert(Serializer& serializer, const PitchRollAiding::Response& self) +{ + insert(serializer, self.source); + +} +void extract(Serializer& serializer, PitchRollAiding::Response& self) +{ + extract(serializer, self.source); + +} + +TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(sourceOut); + extract(deserializer, *sourceOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult savePitchRollAiding(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadPitchRollAiding(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultPitchRollAiding(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const AutoZupt& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.enable); + + insert(serializer, self.threshold); + + } +} +void extract(Serializer& serializer, AutoZupt& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.enable); + + extract(serializer, self.threshold); + + } +} + +void insert(Serializer& serializer, const AutoZupt::Response& self) +{ + insert(serializer, self.enable); + + insert(serializer, self.threshold); + +} +void extract(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, enable); + + insert(serializer, threshold); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_ZUPT_CONTROL, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(enableOut); + extract(deserializer, *enableOut); + + assert(thresholdOut); + extract(deserializer, *thresholdOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveAutoZupt(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadAutoZupt(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultAutoZupt(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const AutoAngularZupt& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.enable); + + insert(serializer, self.threshold); + + } +} +void extract(Serializer& serializer, AutoAngularZupt& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.enable); + + extract(serializer, self.threshold); + + } +} + +void insert(Serializer& serializer, const AutoAngularZupt::Response& self) +{ + insert(serializer, self.enable); + + insert(serializer, self.threshold); + +} +void extract(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, enable); + + insert(serializer, threshold); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(enableOut); + extract(deserializer, *enableOut); + + assert(thresholdOut); + extract(deserializer, *thresholdOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveAutoAngularZupt(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadAutoAngularZupt(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultAutoAngularZupt(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const CommandedZupt& self) +{ + (void)serializer; + (void)self; +} +void extract(Serializer& serializer, CommandedZupt& self) +{ + (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(Serializer& serializer, const CommandedAngularZupt& self) +{ + (void)serializer; + (void)self; +} +void extract(Serializer& serializer, CommandedAngularZupt& self) +{ + (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(Serializer& serializer, const MagCaptureAutoCal& self) +{ + insert(serializer, self.function); + +} +void extract(Serializer& serializer, MagCaptureAutoCal& self) +{ + extract(serializer, self.function); + +} + +TypedResult writeMagCaptureAutoCal(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult saveMagCaptureAutoCal(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const GravityNoise& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.noise[i]); + + } +} +void extract(Serializer& serializer, GravityNoise& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.noise[i]); + + } +} + +void insert(Serializer& 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) +{ + 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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_GRAVITY_NOISE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(noiseOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveGravityNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadGravityNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultGravityNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const PressureAltitudeNoise& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.noise); + + } +} +void extract(Serializer& serializer, PressureAltitudeNoise& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.noise); + + } +} + +void insert(Serializer& serializer, const PressureAltitudeNoise::Response& self) +{ + insert(serializer, self.noise); + +} +void extract(Serializer& serializer, PressureAltitudeNoise::Response& self) +{ + extract(serializer, self.noise); + +} + +TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_PRESSURE_NOISE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(noiseOut); + extract(deserializer, *noiseOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult savePressureAltitudeNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadPressureAltitudeNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const HardIronOffsetNoise& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.noise[i]); + + } +} +void extract(Serializer& serializer, HardIronOffsetNoise& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.noise[i]); + + } +} + +void insert(Serializer& 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) +{ + 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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(noiseOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveHardIronOffsetNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadHardIronOffsetNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const SoftIronMatrixNoise& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 9; i++) + insert(serializer, self.noise[i]); + + } +} +void extract(Serializer& serializer, SoftIronMatrixNoise& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 9; i++) + extract(serializer, self.noise[i]); + + } +} + +void insert(Serializer& 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) +{ + 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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(noise || (9 == 0)); + for(unsigned int i=0; i < 9; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(noiseOut || (9 == 0)); + for(unsigned int i=0; i < 9; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveSoftIronMatrixNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const MagNoise& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.noise[i]); + + } +} +void extract(Serializer& serializer, MagNoise& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.noise[i]); + + } +} + +void insert(Serializer& 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) +{ + 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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + assert(noise || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + insert(serializer, noise[i]); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_MAG_NOISE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(noiseOut || (3 == 0)); + for(unsigned int i=0; i < 3; i++) + extract(deserializer, noiseOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveMagNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadMagNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultMagNoise(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const InclinationSource& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.source); + + insert(serializer, self.inclination); + + } +} +void extract(Serializer& serializer, InclinationSource& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.source); + + extract(serializer, self.inclination); + + } +} + +void insert(Serializer& serializer, const InclinationSource::Response& self) +{ + insert(serializer, self.source); + + insert(serializer, self.inclination); + +} +void extract(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, source); + + insert(serializer, inclination); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_INCLINATION_SOURCE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(sourceOut); + extract(deserializer, *sourceOut); + + assert(inclinationOut); + extract(deserializer, *inclinationOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveInclinationSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadInclinationSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultInclinationSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const MagneticDeclinationSource& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.source); + + insert(serializer, self.declination); + + } +} +void extract(Serializer& serializer, MagneticDeclinationSource& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.source); + + extract(serializer, self.declination); + + } +} + +void insert(Serializer& serializer, const MagneticDeclinationSource::Response& self) +{ + insert(serializer, self.source); + + insert(serializer, self.declination); + +} +void extract(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, source); + + insert(serializer, declination); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_DECLINATION_SOURCE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(sourceOut); + extract(deserializer, *sourceOut); + + assert(declinationOut); + extract(deserializer, *declinationOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveMagneticDeclinationSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadMagneticDeclinationSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const MagFieldMagnitudeSource& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.source); + + insert(serializer, self.magnitude); + + } +} +void extract(Serializer& serializer, MagFieldMagnitudeSource& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.source); + + extract(serializer, self.magnitude); + + } +} + +void insert(Serializer& serializer, const MagFieldMagnitudeSource::Response& self) +{ + insert(serializer, self.source); + + insert(serializer, self.magnitude); + +} +void extract(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, source); + + insert(serializer, magnitude); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(sourceOut); + extract(deserializer, *sourceOut); + + assert(magnitudeOut); + extract(deserializer, *magnitudeOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveMagFieldMagnitudeSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const ReferencePosition& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + insert(serializer, self.enable); + + insert(serializer, self.latitude); + + insert(serializer, self.longitude); + + insert(serializer, self.altitude); + + } +} +void extract(Serializer& serializer, ReferencePosition& self) +{ + extract(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + extract(serializer, self.enable); + + extract(serializer, self.latitude); + + extract(serializer, self.longitude); + + extract(serializer, self.altitude); + + } +} + +void insert(Serializer& serializer, const ReferencePosition::Response& self) +{ + insert(serializer, self.enable); + + insert(serializer, self.latitude); + + insert(serializer, self.longitude); + + insert(serializer, self.altitude); + +} +void extract(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[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + insert(serializer, FunctionSelector::WRITE); + insert(serializer, enable); + + insert(serializer, latitude); + + insert(serializer, longitude); + + insert(serializer, altitude); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); +} +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)); + + 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)mip_serializer_length(&serializer), REPLY_REFERENCE_POSITION, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(enableOut); + extract(deserializer, *enableOut); + + assert(latitudeOut); + extract(deserializer, *latitudeOut); + + assert(longitudeOut); + extract(deserializer, *longitudeOut); + + assert(altitudeOut); + extract(deserializer, *altitudeOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveReferencePosition(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult loadReferencePosition(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer 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)mip_serializer_length(&serializer)); +} +TypedResult defaultReferencePosition(C::mip_interface& device) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + 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)mip_serializer_length(&serializer)); +} +void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self) +{ + insert(serializer, self.function); + + if( self.function == FunctionSelector::WRITE ) + { + 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(Serializer& serializer, AltitudeAiding& self) +void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self) { extract(serializer, self.function); if( self.function == FunctionSelector::WRITE ) { - extract(serializer, self.aiding_selector); + 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); } } -void insert(Serializer& serializer, const AltitudeAiding::Response& self) +void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self) { - insert(serializer, self.aiding_selector); + 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(Serializer& serializer, AltitudeAiding::Response& self) +void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self) { - extract(serializer, self.aiding_selector); + 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); } -CmdResult writeAltitudeAiding(C::mip_interface& device, uint8_t aidingSelector) +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)); insert(serializer, FunctionSelector::WRITE); - insert(serializer, aidingSelector); + insert(serializer, adaptiveMeasurement); + + insert(serializer, frequency); + + insert(serializer, lowLimit); + + insert(serializer, highLimit); + + insert(serializer, lowLimitUncertainty); + + insert(serializer, highLimitUncertainty); + + insert(serializer, minimumUncertainty); 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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAltitudeAiding(C::mip_interface& device, uint8_t* aidingSelectorOut) +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)); @@ -1311,21 +3378,39 @@ CmdResult readAltitudeAiding(C::mip_interface& device, uint8_t* aidingSelectorOu assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { Serializer deserializer(buffer, responseLength); - assert(aidingSelectorOut); - extract(deserializer, *aidingSelectorOut); + assert(adaptiveMeasurementOut); + extract(deserializer, *adaptiveMeasurementOut); + + assert(frequencyOut); + extract(deserializer, *frequencyOut); + + assert(lowLimitOut); + extract(deserializer, *lowLimitOut); + + assert(highLimitOut); + extract(deserializer, *highLimitOut); + + assert(lowLimitUncertaintyOut); + extract(deserializer, *lowLimitUncertaintyOut); + + assert(highLimitUncertaintyOut); + extract(deserializer, *highLimitUncertaintyOut); + + assert(minimumUncertaintyOut); + extract(deserializer, *minimumUncertaintyOut); if( deserializer.remaining() != 0 ) result = MIP_STATUS_ERROR; } return result; } -CmdResult saveAltitudeAiding(C::mip_interface& device) +TypedResult saveAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1333,9 +3418,9 @@ CmdResult 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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAltitudeAiding(C::mip_interface& device) +TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1343,9 +3428,9 @@ CmdResult 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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAltitudeAiding(C::mip_interface& device) +TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1353,63 +3438,113 @@ CmdResult 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_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -void insert(Serializer& serializer, const AutoZupt& self) +void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self) { insert(serializer, self.function); if( self.function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + insert(serializer, self.adaptive_measurement); - insert(serializer, self.threshold); + 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(Serializer& serializer, AutoZupt& self) +void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self) { extract(serializer, self.function); if( self.function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + extract(serializer, self.adaptive_measurement); - extract(serializer, self.threshold); + 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); } } -void insert(Serializer& serializer, const AutoZupt::Response& self) +void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self) { - insert(serializer, self.enable); + insert(serializer, self.adaptive_measurement); - insert(serializer, self.threshold); + 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(Serializer& serializer, AutoZupt::Response& self) +void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self) { - extract(serializer, self.enable); + extract(serializer, self.adaptive_measurement); - extract(serializer, self.threshold); + 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); } -CmdResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold) +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)); insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + insert(serializer, adaptiveMeasurement); - insert(serializer, threshold); + insert(serializer, frequency); + + insert(serializer, lowLimit); + + insert(serializer, highLimit); + + insert(serializer, lowLimitUncertainty); + + insert(serializer, highLimitUncertainty); + + insert(serializer, minimumUncertainty); 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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) +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)); @@ -1418,24 +3553,39 @@ CmdResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thre assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { Serializer deserializer(buffer, responseLength); - assert(enableOut); - extract(deserializer, *enableOut); + assert(adaptiveMeasurementOut); + extract(deserializer, *adaptiveMeasurementOut); - assert(thresholdOut); - extract(deserializer, *thresholdOut); + assert(frequencyOut); + extract(deserializer, *frequencyOut); + + assert(lowLimitOut); + extract(deserializer, *lowLimitOut); + + assert(highLimitOut); + extract(deserializer, *highLimitOut); + + assert(lowLimitUncertaintyOut); + extract(deserializer, *lowLimitUncertaintyOut); + + assert(highLimitUncertaintyOut); + extract(deserializer, *highLimitUncertaintyOut); + + assert(minimumUncertaintyOut); + extract(deserializer, *minimumUncertaintyOut); if( deserializer.remaining() != 0 ) result = MIP_STATUS_ERROR; } return result; } -CmdResult saveAutoZupt(C::mip_interface& device) +TypedResult saveMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1443,9 +3593,9 @@ CmdResult 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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAutoZupt(C::mip_interface& device) +TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1453,9 +3603,9 @@ CmdResult 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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAutoZupt(C::mip_interface& device) +TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1463,9 +3613,9 @@ CmdResult 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_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -void insert(Serializer& serializer, const AutoAngularZupt& self) +void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self) { insert(serializer, self.function); @@ -1473,11 +3623,17 @@ void insert(Serializer& serializer, const AutoAngularZupt& self) { insert(serializer, self.enable); - insert(serializer, self.threshold); + insert(serializer, self.frequency); + + insert(serializer, self.high_limit); + + insert(serializer, self.high_limit_uncertainty); + + insert(serializer, self.minimum_uncertainty); } } -void extract(Serializer& serializer, AutoAngularZupt& self) +void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self) { extract(serializer, self.function); @@ -1485,27 +3641,45 @@ void extract(Serializer& serializer, AutoAngularZupt& self) { extract(serializer, self.enable); - extract(serializer, self.threshold); + extract(serializer, self.frequency); + + extract(serializer, self.high_limit); + + extract(serializer, self.high_limit_uncertainty); + + extract(serializer, self.minimum_uncertainty); } } -void insert(Serializer& serializer, const AutoAngularZupt::Response& self) +void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self) { insert(serializer, self.enable); - insert(serializer, self.threshold); + insert(serializer, self.frequency); + + insert(serializer, self.high_limit); + + insert(serializer, self.high_limit_uncertainty); + + insert(serializer, self.minimum_uncertainty); } -void extract(Serializer& serializer, AutoAngularZupt::Response& self) +void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self) { extract(serializer, self.enable); - extract(serializer, self.threshold); + extract(serializer, self.frequency); + + extract(serializer, self.high_limit); + + extract(serializer, self.high_limit_uncertainty); + + extract(serializer, self.minimum_uncertainty); } -CmdResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold) +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)); @@ -1513,13 +3687,19 @@ CmdResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float t insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); - insert(serializer, threshold); + insert(serializer, frequency); + + insert(serializer, highLimit); + + insert(serializer, highLimitUncertainty); + + insert(serializer, minimumUncertainty); 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_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) +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)); @@ -1528,7 +3708,7 @@ CmdResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, floa assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1537,15 +3717,24 @@ CmdResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, floa assert(enableOut); extract(deserializer, *enableOut); - assert(thresholdOut); - extract(deserializer, *thresholdOut); + assert(frequencyOut); + extract(deserializer, *frequencyOut); + + assert(highLimitOut); + extract(deserializer, *highLimitOut); + + assert(highLimitUncertaintyOut); + extract(deserializer, *highLimitUncertaintyOut); + + assert(minimumUncertaintyOut); + extract(deserializer, *minimumUncertaintyOut); if( deserializer.remaining() != 0 ) result = MIP_STATUS_ERROR; } return result; } -CmdResult saveAutoAngularZupt(C::mip_interface& device) +TypedResult saveMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1553,9 +3742,9 @@ CmdResult 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_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAutoAngularZupt(C::mip_interface& device) +TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1563,9 +3752,9 @@ CmdResult 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_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAutoAngularZupt(C::mip_interface& device) +TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1573,37 +3762,7 @@ CmdResult 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)); -} -void insert(Serializer& serializer, const CommandedZupt& self) -{ - (void)serializer; - (void)self; -} -void extract(Serializer& serializer, CommandedZupt& self) -{ - (void)serializer; - (void)self; -} - -CmdResult 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)serializer; - (void)self; -} -void extract(Serializer& serializer, CommandedAngularZupt& self) -{ - (void)serializer; - (void)self; -} - -CmdResult commandedAngularZupt(C::mip_interface& device) -{ - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMMANDED_ANGULAR_ZUPT, NULL, 0); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } void insert(Serializer& serializer, const AidingMeasurementEnable& self) { @@ -1645,7 +3804,7 @@ void extract(Serializer& serializer, AidingMeasurementEnable::Response& self) } -CmdResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) +TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1659,7 +3818,7 @@ CmdResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasureme return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) +TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1670,7 +3829,7 @@ CmdResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasuremen assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1686,7 +3845,7 @@ CmdResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasuremen } return result; } -CmdResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) +TypedResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1698,7 +3857,7 @@ CmdResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasuremen return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) +TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1710,7 +3869,7 @@ CmdResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasuremen return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) +TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1733,7 +3892,7 @@ void extract(Serializer& serializer, Run& self) (void)self; } -CmdResult run(C::mip_interface& device) +TypedResult run(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RUN, NULL, 0); } @@ -1785,7 +3944,7 @@ void extract(Serializer& serializer, KinematicConstraint::Response& self) } -CmdResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection) +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)); @@ -1801,7 +3960,7 @@ CmdResult writeKinematicConstraint(C::mip_interface& device, uint8_t acceleratio return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) +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)); @@ -1810,7 +3969,7 @@ CmdResult readKinematicConstraint(C::mip_interface& device, uint8_t* acceleratio assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1830,7 +3989,7 @@ CmdResult readKinematicConstraint(C::mip_interface& device, uint8_t* acceleratio } return result; } -CmdResult saveKinematicConstraint(C::mip_interface& device) +TypedResult saveKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1840,7 +3999,7 @@ CmdResult saveKinematicConstraint(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadKinematicConstraint(C::mip_interface& device) +TypedResult loadKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1850,7 +4009,7 @@ CmdResult loadKinematicConstraint(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultKinematicConstraint(C::mip_interface& device) +TypedResult defaultKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -1964,7 +4123,7 @@ void extract(Serializer& serializer, InitializationConfiguration::Response& self } -CmdResult 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 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)); @@ -1996,7 +4155,7 @@ CmdResult writeInitializationConfiguration(C::mip_interface& device, uint8_t wai return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult 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 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)); @@ -2005,7 +4164,7 @@ CmdResult readInitializationConfiguration(C::mip_interface& device, uint8_t* wai assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2045,7 +4204,7 @@ CmdResult readInitializationConfiguration(C::mip_interface& device, uint8_t* wai } return result; } -CmdResult saveInitializationConfiguration(C::mip_interface& device) +TypedResult saveInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2055,7 +4214,7 @@ CmdResult saveInitializationConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadInitializationConfiguration(C::mip_interface& device) +TypedResult loadInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2065,7 +4224,7 @@ CmdResult loadInitializationConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultInitializationConfiguration(C::mip_interface& device) +TypedResult defaultInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2115,7 +4274,7 @@ void extract(Serializer& serializer, AdaptiveFilterOptions::Response& self) } -CmdResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit) +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)); @@ -2129,7 +4288,7 @@ CmdResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, ui return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) +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)); @@ -2138,7 +4297,7 @@ CmdResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2155,7 +4314,7 @@ CmdResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, } return result; } -CmdResult saveAdaptiveFilterOptions(C::mip_interface& device) +TypedResult saveAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2165,7 +4324,7 @@ CmdResult saveAdaptiveFilterOptions(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadAdaptiveFilterOptions(C::mip_interface& device) +TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2175,7 +4334,7 @@ CmdResult loadAdaptiveFilterOptions(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultAdaptiveFilterOptions(C::mip_interface& device) +TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2229,7 +4388,7 @@ void extract(Serializer& serializer, MultiAntennaOffset::Response& self) } -CmdResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset) +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)); @@ -2245,7 +4404,7 @@ CmdResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) +TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2256,7 +4415,7 @@ CmdResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, f assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2273,7 +4432,7 @@ CmdResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, f } return result; } -CmdResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) +TypedResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2285,7 +4444,7 @@ CmdResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) +TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2297,7 +4456,7 @@ CmdResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) +TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2361,7 +4520,7 @@ void extract(Serializer& serializer, RelPosConfiguration::Response& self) } -CmdResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates) +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)); @@ -2379,7 +4538,7 @@ CmdResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, Fil return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) +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)); @@ -2388,7 +4547,7 @@ CmdResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2409,7 +4568,7 @@ CmdResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, } return result; } -CmdResult saveRelPosConfiguration(C::mip_interface& device) +TypedResult saveRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2419,7 +4578,7 @@ CmdResult saveRelPosConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadRelPosConfiguration(C::mip_interface& device) +TypedResult loadRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2429,7 +4588,7 @@ CmdResult loadRelPosConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultRelPosConfiguration(C::mip_interface& device) +TypedResult defaultRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2483,7 +4642,7 @@ void extract(Serializer& serializer, RefPointLeverArm::Response& self) } -CmdResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset) +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)); @@ -2499,7 +4658,7 @@ CmdResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::Refe return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) +TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2508,7 +4667,7 @@ CmdResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::Refer assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2526,7 +4685,7 @@ CmdResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::Refer } return result; } -CmdResult saveRefPointLeverArm(C::mip_interface& device) +TypedResult saveRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2536,7 +4695,7 @@ CmdResult saveRefPointLeverArm(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadRefPointLeverArm(C::mip_interface& device) +TypedResult loadRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2546,7 +4705,7 @@ CmdResult loadRefPointLeverArm(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultRefPointLeverArm(C::mip_interface& device) +TypedResult defaultRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2579,7 +4738,7 @@ void extract(Serializer& serializer, SpeedMeasurement& self) } -CmdResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty) +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)); @@ -2640,7 +4799,7 @@ void extract(Serializer& serializer, SpeedLeverArm::Response& self) } -CmdResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset) +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)); @@ -2656,7 +4815,7 @@ CmdResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const flo return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) +TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2667,7 +4826,7 @@ CmdResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* lev assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2684,7 +4843,7 @@ CmdResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* lev } return result; } -CmdResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) +TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2696,7 +4855,7 @@ CmdResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) +TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2708,7 +4867,7 @@ CmdResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) +TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2752,7 +4911,7 @@ void extract(Serializer& serializer, WheeledVehicleConstraintControl::Response& } -CmdResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) +TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2764,7 +4923,7 @@ CmdResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) +TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2773,7 +4932,7 @@ CmdResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2787,7 +4946,7 @@ CmdResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* } return result; } -CmdResult saveWheeledVehicleConstraintControl(C::mip_interface& device) +TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2797,7 +4956,7 @@ CmdResult saveWheeledVehicleConstraintControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadWheeledVehicleConstraintControl(C::mip_interface& device) +TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2807,7 +4966,7 @@ CmdResult loadWheeledVehicleConstraintControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) +TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2849,7 +5008,7 @@ void extract(Serializer& serializer, VerticalGyroConstraintControl::Response& se } -CmdResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) +TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2861,7 +5020,7 @@ CmdResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t e return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) +TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2870,7 +5029,7 @@ CmdResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* e assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2884,7 +5043,7 @@ CmdResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* e } return result; } -CmdResult saveVerticalGyroConstraintControl(C::mip_interface& device) +TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2894,7 +5053,7 @@ CmdResult saveVerticalGyroConstraintControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadVerticalGyroConstraintControl(C::mip_interface& device) +TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2904,7 +5063,7 @@ CmdResult loadVerticalGyroConstraintControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultVerticalGyroConstraintControl(C::mip_interface& device) +TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2954,7 +5113,7 @@ void extract(Serializer& serializer, GnssAntennaCalControl::Response& self) } -CmdResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) +TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2968,7 +5127,7 @@ CmdResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) +TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -2977,7 +5136,7 @@ CmdResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2994,7 +5153,7 @@ CmdResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut } return result; } -CmdResult saveGnssAntennaCalControl(C::mip_interface& device) +TypedResult saveGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3004,7 +5163,7 @@ CmdResult saveGnssAntennaCalControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadGnssAntennaCalControl(C::mip_interface& device) +TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3014,7 +5173,7 @@ CmdResult loadGnssAntennaCalControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultGnssAntennaCalControl(C::mip_interface& device) +TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -3024,116 +5183,6 @@ CmdResult defaultGnssAntennaCalControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); } -void insert(Serializer& serializer, const MagneticDeclinationSource& self) -{ - insert(serializer, self.function); - - if( self.function == FunctionSelector::WRITE ) - { - insert(serializer, self.source); - - insert(serializer, self.declination); - - } -} -void extract(Serializer& serializer, MagneticDeclinationSource& self) -{ - extract(serializer, self.function); - - if( self.function == FunctionSelector::WRITE ) - { - extract(serializer, self.source); - - extract(serializer, self.declination); - - } -} - -void insert(Serializer& serializer, const MagneticDeclinationSource::Response& self) -{ - insert(serializer, self.source); - - insert(serializer, self.declination); - -} -void extract(Serializer& serializer, MagneticDeclinationSource::Response& self) -{ - extract(serializer, self.source); - - extract(serializer, self.declination); - -} - -CmdResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagDeclinationSource source, float declination) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); - - insert(serializer, declination); - - assert(serializer.isOk()); - - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); -} -CmdResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagDeclinationSource* sourceOut, float* declinationOut) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - insert(serializer, FunctionSelector::READ); - assert(serializer.isOk()); - - uint8_t responseLength = sizeof(buffer); - CmdResult 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); - - if( result == MIP_ACK_OK ) - { - Serializer deserializer(buffer, responseLength); - - assert(sourceOut); - extract(deserializer, *sourceOut); - - assert(declinationOut); - extract(deserializer, *declinationOut); - - if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; - } - return result; -} -CmdResult saveMagneticDeclinationSource(C::mip_interface& device) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer 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)mip_serializer_length(&serializer)); -} -CmdResult loadMagneticDeclinationSource(C::mip_interface& device) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer 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)mip_serializer_length(&serializer)); -} -CmdResult defaultMagneticDeclinationSource(C::mip_interface& device) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - 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)mip_serializer_length(&serializer)); -} void insert(Serializer& serializer, const SetInitialHeading& self) { insert(serializer, self.heading); @@ -3145,7 +5194,7 @@ void extract(Serializer& serializer, SetInitialHeading& self) } -CmdResult setInitialHeading(C::mip_interface& device, float heading) +TypedResult setInitialHeading(C::mip_interface& device, float heading) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); diff --git a/src/mip/definitions/commands_filter.h b/src/mip/definitions/commands_filter.h index c680272d4..1c48785ec 100644 --- a/src/mip/definitions/commands_filter.h +++ b/src/mip/definitions/commands_filter.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -162,13 +163,21 @@ static const mip_filter_reference_frame MIP_FILTER_REFERENCE_FRAME_LLH = 2; /// 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); -typedef uint8_t mip_filter_mag_declination_source; -static const mip_filter_mag_declination_source MIP_FILTER_MAG_DECLINATION_SOURCE_NONE = 1; ///< Magnetic field is assumed to have an declination angle equal to zero. -static const mip_filter_mag_declination_source MIP_FILTER_MAG_DECLINATION_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_declination_source MIP_FILTER_MAG_DECLINATION_SOURCE_MANUAL = 3; ///< Magnetic field is assumed to have the declination angle specified by the user. +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_declination_source(struct mip_serializer* serializer, const mip_filter_mag_declination_source self); -void extract_mip_filter_mag_declination_source(struct mip_serializer* serializer, mip_filter_mag_declination_source* self); +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); + +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); //////////////////////////////////////////////////////////////////////////////// @@ -185,6 +194,7 @@ void extract_mip_filter_mag_declination_source(struct mip_serializer* serializer ///@{ mip_cmd_result mip_filter_reset(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -216,6 +226,7 @@ void insert_mip_filter_set_initial_attitude_command(struct mip_serializer* seria void extract_mip_filter_set_initial_attitude_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -243,6 +254,7 @@ 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_ANTENNA_OFFSET = 0x0010; ///< 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; struct mip_filter_estimation_control_command { @@ -271,6 +283,7 @@ 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_cmd_result mip_filter_load_estimation_control(struct mip_interface* device); mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -290,9 +303,9 @@ struct mip_filter_external_gnss_update_command double latitude; ///< [degrees] double longitude; ///< [degrees] double height; ///< Above WGS84 ellipsoid [meters] - float velocity[3]; ///< NED Frame [meters/second] - float pos_uncertainty[3]; ///< NED Frame, 1-sigma [meters] - float vel_uncertainty[3]; ///< NED Frame, 1-sigma [meters/second] + 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; @@ -300,6 +313,7 @@ void insert_mip_filter_external_gnss_update_command(struct mip_serializer* seria void extract_mip_filter_external_gnss_update_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -332,6 +346,7 @@ void insert_mip_filter_external_heading_update_command(struct mip_serializer* se void extract_mip_filter_external_heading_update_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -370,6 +385,7 @@ void insert_mip_filter_external_heading_update_with_time_command(struct mip_seri void extract_mip_filter_external_heading_update_with_time_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -387,6 +403,7 @@ 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_ROLL = 0x1; ///< 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; struct mip_filter_tare_orientation_command { @@ -415,6 +432,49 @@ 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_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device); mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_vehicle_dynamics_mode (0x0D,0x10) Vehicle Dynamics Mode [C] +/// Controls the vehicle dynamics mode. +/// +///@{ + +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; ///< + +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(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_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); + +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(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); + +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -473,6 +533,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -512,7 +573,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_in struct mip_filter_sensor_to_vehicle_rotation_dcm_command { mip_function_selector function; - float dcm[9]; + mip_matrix3f dcm; }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_command mip_filter_sensor_to_vehicle_rotation_dcm_command; @@ -521,7 +582,7 @@ void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(struct mip_serial struct mip_filter_sensor_to_vehicle_rotation_dcm_response { - float dcm[9]; + mip_matrix3f dcm; }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_response mip_filter_sensor_to_vehicle_rotation_dcm_response; @@ -533,6 +594,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -571,7 +633,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_inte struct mip_filter_sensor_to_vehicle_rotation_quaternion_command { mip_function_selector function; - float quat[4]; + mip_quatf quat; }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_command mip_filter_sensor_to_vehicle_rotation_quaternion_command; @@ -580,7 +642,7 @@ void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(struct mip struct mip_filter_sensor_to_vehicle_rotation_quaternion_response { - float quat[4]; + mip_quatf quat; }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_response mip_filter_sensor_to_vehicle_rotation_quaternion_response; @@ -592,6 +654,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -611,7 +674,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct m struct mip_filter_sensor_to_vehicle_offset_command { mip_function_selector function; - float offset[3]; ///< [meters] + mip_vector3f offset; ///< [meters] }; typedef struct mip_filter_sensor_to_vehicle_offset_command mip_filter_sensor_to_vehicle_offset_command; @@ -620,7 +683,7 @@ void extract_mip_filter_sensor_to_vehicle_offset_command(struct mip_serializer* struct mip_filter_sensor_to_vehicle_offset_response { - float offset[3]; ///< [meters] + mip_vector3f offset; ///< [meters] }; typedef struct mip_filter_sensor_to_vehicle_offset_response mip_filter_sensor_to_vehicle_offset_response; @@ -632,6 +695,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -648,7 +712,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* struct mip_filter_antenna_offset_command { mip_function_selector function; - float offset[3]; ///< [meters] + mip_vector3f offset; ///< [meters] }; typedef struct mip_filter_antenna_offset_command mip_filter_antenna_offset_command; @@ -657,7 +721,7 @@ void extract_mip_filter_antenna_offset_command(struct mip_serializer* serializer struct mip_filter_antenna_offset_response { - float offset[3]; ///< [meters] + mip_vector3f offset; ///< [meters] }; typedef struct mip_filter_antenna_offset_response mip_filter_antenna_offset_response; @@ -669,6 +733,7 @@ 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_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device); mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -714,6 +779,7 @@ 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_cmd_result mip_filter_load_gnss_source(struct mip_interface* device); mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -736,7 +802,7 @@ 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; ///< Seen notes 1,2 +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; ///< @@ -770,6 +836,7 @@ 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_cmd_result mip_filter_load_heading_source(struct mip_interface* device); mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -810,54 +877,250 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_altitude_aiding (0x0D,0x47) Altitude Aiding [C] -/// Altitude Aiding Control +///@defgroup c_filter_accel_noise (0x0D,0x1A) Accel Noise [C] +/// Accelerometer Noise Standard Deviation /// -/// 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 GNSS outages. +/// Each of the noise values must be greater than 0.0. /// -/// Possible altitude aiding selector values: +/// The 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 the performance of the filter. +/// Default values provide good performance for most laboratory conditions. +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_gyro_noise (0x0D,0x1B) Gyro Noise [C] +/// Gyroscope Noise Standard Deviation /// -/// 0x00 - No altitude aiding (disable) -/// 0x01 - Enable pressure sensor aiding(1) +/// Each of the noise values must be greater than 0.0 /// -/// 1. Pressure altitude is based on "instant sea level pressure" which is dependent on location and weather conditions and can vary by more than 40 meters. +/// The 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 the performance of the filter. +/// Default values provide good performance for most laboratory conditions. +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_accel_bias_model (0x0D,0x1C) Accel Bias Model [C] +/// Accelerometer Bias Model Parameters +/// +/// Noise values must be greater than 0.0 +/// +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_gyro_bias_model (0x0D,0x1D) Gyro Bias Model [C] +/// Gyroscope Bias Model Parameters +/// +/// Noise values must be greater than 0.0 /// /// ///@{ +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_altitude_aiding (0x0D,0x47) Altitude Aiding [C] +/// 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. +/// +/// Pressure altitude is based on "instant sea level pressure" which is dependent on location and weather conditions and can vary by more than 40 meters. +/// +/// +///@{ + +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 + struct mip_filter_altitude_aiding_command { mip_function_selector function; - uint8_t aiding_selector; ///< See above + 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(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_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); + struct mip_filter_altitude_aiding_response { - uint8_t aiding_selector; ///< See above + 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(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); -mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, uint8_t aiding_selector); -mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, uint8_t* aiding_selector_out); +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_pitch_roll_aiding (0x0D,0x4B) Pitch Roll Aiding [C] +/// 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. +/// +///@{ + +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 + +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(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_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); + +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(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); + +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_filter_auto_zupt (0x0D,0x1E) Auto Zupt [C] -/// Zero Velocity Update /// 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.) /// @@ -889,6 +1152,7 @@ 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_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device); mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -925,26 +1189,563 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_filter_commanded_zupt (0x0D,0x22) Commanded Zupt [C] -/// Commanded Zero Velocity Update /// Please see the device user manual for the maximum rate of this message. /// ///@{ mip_cmd_result mip_filter_commanded_zupt(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_filter_commanded_angular_zupt (0x0D,0x23) Commanded Angular Zupt [C] -/// Commanded Zero Angular Rate Update /// Please see the device user manual for the maximum rate of this message. /// ///@{ mip_cmd_result mip_filter_commanded_angular_zupt(struct mip_interface* device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_mag_capture_auto_cal (0x0D,0x27) Mag Capture Auto Cal [C] +/// 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. +/// +///@{ + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_gravity_noise (0x0D,0x28) Gravity Noise [C] +/// 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 +/// +/// The 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. +/// Default values provide good performance for most laboratory conditions. +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_pressure_altitude_noise (0x0D,0x29) Pressure Altitude Noise [C] +/// 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 +/// +/// This noise value represents pressure altitude model noise in the Estimation Filter. +/// A 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. +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_hard_iron_offset_noise (0x0D,0x2B) Hard Iron Offset Noise [C] +/// 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. +/// +/// Noise values must be greater than 0.0 +/// +/// The noise values represent process noise in the Estimation Filter. +/// Changing 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. +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_soft_iron_matrix_noise (0x0D,0x2C) Soft Iron Matrix Noise [C] +/// Set the expected soft iron matrix noise 1-sigma values. +/// This function can be used to tune the filter performance in the target application. +/// +/// Noise values must be greater than 0.0 +/// +/// The 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 the performance of the filter. Default values provide good performance for most laboratory conditions. +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_mag_noise (0x0D,0x42) Mag Noise [C] +/// Set the expected magnetometer noise 1-sigma values. +/// This function can be used to tune the filter performance in the target application. +/// +/// Noise values must be greater than 0.0 (gauss) +/// +/// The 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 the performance of the filter. Default values provide good performance for most laboratory conditions +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_inclination_source (0x0D,0x4C) Inclination Source [C] +/// 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. +/// Having 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. +/// +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_magnetic_declination_source (0x0D,0x43) Magnetic Declination Source [C] +/// 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. +/// Having 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. +/// +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_mag_field_magnitude_source (0x0D,0x4D) Mag Field Magnitude Source [C] +/// Set/Get the local magnetic field magnitude source. +/// +/// This is used to specify the local magnitude of the earth's magnetic field. +/// Having 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. +/// +///@{ + +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(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); + +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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_reference_position (0x0D,0x26) Reference Position [C] +/// 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. +/// +/// +///@{ + +struct mip_filter_reference_position_command +{ + mip_function_selector function; + bool enable; ///< enable/disable + 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(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); + +struct mip_filter_reference_position_response +{ + bool enable; ///< enable/disable + 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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_accel_magnitude_error_adaptive_measurement (0x0D,0x44) Accel Magnitude Error Adaptive Measurement [C] +/// Enable or disable the gravity magnitude error adaptive measurement. +/// This function can be used to tune the filter performance in the target application +/// +/// Pick values that give you the least occurrence of invalid EF attitude output. +/// The default values are good for standard low dynamics applications. +/// Increase values for higher dynamic conditions, lower values for lower dynamic. +/// Too low a value will result in excessive heading errors. +/// Higher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc. +/// +/// 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. +/// Instead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality. +/// +/// +///@{ + +struct mip_filter_accel_magnitude_error_adaptive_measurement_command +{ + mip_function_selector function; + mip_filter_adaptive_measurement adaptive_measurement; ///< Adaptive measurement selector + float frequency; ///< Low-pass filter curoff frequency [hertz] + float low_limit; ///< [meters/second^2] + float high_limit; ///< [meters/second^2] + 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(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); + +struct mip_filter_accel_magnitude_error_adaptive_measurement_response +{ + mip_filter_adaptive_measurement adaptive_measurement; ///< Adaptive measurement selector + float frequency; ///< Low-pass filter curoff frequency [hertz] + float low_limit; ///< [meters/second^2] + float high_limit; ///< [meters/second^2] + 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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_mag_magnitude_error_adaptive_measurement (0x0D,0x45) Mag Magnitude Error Adaptive Measurement [C] +/// 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). +/// +/// Pick values that give you the least occurrence of invalid EF attitude output. +/// The default values are good for standard low dynamics applications. +/// Increase values for higher dynamic conditions, lower values for lower dynamic. +/// Too low a value will result in excessive heading errors. +/// Higher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc. +/// +/// +///@{ + +struct mip_filter_mag_magnitude_error_adaptive_measurement_command +{ + mip_function_selector function; + mip_filter_adaptive_measurement adaptive_measurement; ///< Adaptive measurement selector + float frequency; ///< Low-pass filter curoff frequency [hertz] + float low_limit; ///< [meters/second^2] + float high_limit; ///< [meters/second^2] + 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(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); + +struct mip_filter_mag_magnitude_error_adaptive_measurement_response +{ + mip_filter_adaptive_measurement adaptive_measurement; ///< Adaptive measurement selector + float frequency; ///< Low-pass filter curoff frequency [hertz] + float low_limit; ///< [meters/second^2] + float high_limit; ///< [meters/second^2] + 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(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); + +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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_mag_dip_angle_error_adaptive_measurement (0x0D,0x46) Mag Dip Angle Error Adaptive Measurement [C] +/// Enable or disable the magnetometer dip angle error adaptive measurement. +/// This function can be used to tune the filter performance in the target application +/// +/// Pick values that give you the least occurrence of invalid EF attitude output. +/// The default values are good for standard low dynamics applications. +/// Increase values for higher dynamic conditions, lower values for lower dynamic. +/// Too low a value will result in excessive heading errors. +/// Higher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc. +/// +/// The magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected. +/// +/// +///@{ + +struct mip_filter_mag_dip_angle_error_adaptive_measurement_command +{ + mip_function_selector function; + bool enable; ///< Enable/Disable + float frequency; ///< Low-pass filter curoff frequency [hertz] + 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(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); + +struct mip_filter_mag_dip_angle_error_adaptive_measurement_response +{ + bool enable; ///< Enable/Disable + float frequency; ///< Low-pass filter curoff frequency [hertz] + 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(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); + +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -956,19 +1757,22 @@ mip_cmd_result mip_filter_commanded_angular_zupt(struct mip_interface* device); ///@{ 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; ///< Altimeter -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 -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_ALL = 65535; ///< Save/load/reset all options +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_BODY_FRAME_VEL = 8; ///< External body 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 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 sorce + bool enable; ///< Controls the aiding source }; typedef struct mip_filter_aiding_measurement_enable_command mip_filter_aiding_measurement_enable_command; @@ -981,7 +1785,7 @@ void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct m 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 sorce + bool enable; ///< Controls the aiding source }; typedef struct mip_filter_aiding_measurement_enable_response mip_filter_aiding_measurement_enable_response; @@ -993,6 +1797,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1004,6 +1809,7 @@ mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface ///@{ mip_cmd_result mip_filter_run(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1042,6 +1848,7 @@ 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_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device); mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1058,7 +1865,9 @@ typedef uint8_t mip_filter_initialization_configuration_command_alignment_select static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_NONE = 0x00; static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_DUAL_ANTENNA = 0x01; ///< Dual-antenna GNSS alignment static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_KINEMATIC = 0x02; ///< GNSS kinematic alignment (GNSS velocity determines initial heading) -static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_MAGNETOMETER = 0x04; ///< Magnetometer heading alignment +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; 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 @@ -1075,8 +1884,8 @@ struct mip_filter_initialization_configuration_command float initial_heading; ///< User-specified initial platform heading (degrees). float initial_pitch; ///< User-specified initial platform pitch (degrees) float initial_roll; ///< User-specified initial platform roll (degrees) - float initial_position[3]; ///< User-specified initial platform position (units determined by reference frame selector, see note.) - float initial_velocity[3]; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) + 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 }; @@ -1098,8 +1907,8 @@ struct mip_filter_initialization_configuration_response float initial_heading; ///< User-specified initial platform heading (degrees). float initial_pitch; ///< User-specified initial platform pitch (degrees) float initial_roll; ///< User-specified initial platform roll (degrees) - float initial_position[3]; ///< User-specified initial platform position (units determined by reference frame selector, see note.) - float initial_velocity[3]; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) + 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 }; @@ -1112,6 +1921,7 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1146,6 +1956,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1153,6 +1964,7 @@ mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* /// Set the antenna lever arm. /// /// This command works with devices that utilize multiple antennas. +///

Offset Limit: 10 m magnitude (default) /// ///@{ @@ -1160,7 +1972,7 @@ struct mip_filter_multi_antenna_offset_command { mip_function_selector function; uint8_t receiver_id; ///< Receiver: 1, 2, etc... - float antenna_offset[3]; ///< Antenna lever arm offset vector in the vehicle frame (m) + 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; @@ -1170,7 +1982,7 @@ void extract_mip_filter_multi_antenna_offset_command(struct mip_serializer* seri struct mip_filter_multi_antenna_offset_response { uint8_t receiver_id; - float antenna_offset[3]; + mip_vector3f antenna_offset; }; typedef struct mip_filter_multi_antenna_offset_response mip_filter_multi_antenna_offset_response; @@ -1182,6 +1994,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1195,7 +2008,7 @@ struct mip_filter_rel_pos_configuration_command mip_function_selector function; uint8_t source; ///< 0 - auto (RTK base station), 1 - manual mip_filter_reference_frame reference_frame_selector; ///< ECEF or LLH - double reference_coordinates[3]; ///< reference coordinates, units determined by source selection + 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; @@ -1206,7 +2019,7 @@ 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 - double reference_coordinates[3]; ///< reference coordinates, units determined by source selection + 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; @@ -1218,6 +2031,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1226,8 +2040,10 @@ mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* de /// 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, /// and a velocity offset that depends on vehicle attitude and angular rate. -/// 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. -/// 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) +///
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. +///

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) +///

Offset Limits +///
Reference Point VEH (1): 10 m magnitude (default) /// ///@{ @@ -1238,7 +2054,7 @@ 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 - float lever_arm_offset[3]; ///< [m] Lever arm offset vector in the vehicle's reference frame. + 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; @@ -1251,7 +2067,7 @@ void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(str 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 - float lever_arm_offset[3]; ///< [m] Lever arm offset vector in the vehicle's reference frame. + 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; @@ -1263,6 +2079,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1286,6 +2103,7 @@ void insert_mip_filter_speed_measurement_command(struct mip_serializer* serializ void extract_mip_filter_speed_measurement_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1304,7 +2122,7 @@ struct mip_filter_speed_lever_arm_command { mip_function_selector function; uint8_t source; ///< Reserved, must be 1. - float lever_arm_offset[3]; ///< [m] Lever arm offset vector in the vehicle's reference frame. + 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; @@ -1314,7 +2132,7 @@ void extract_mip_filter_speed_lever_arm_command(struct mip_serializer* serialize struct mip_filter_speed_lever_arm_response { uint8_t source; ///< Reserved, must be 1. - float lever_arm_offset[3]; ///< [m] Lever arm offset vector in the vehicle's reference frame. + 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; @@ -1326,6 +2144,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1336,7 +2155,7 @@ mip_cmd_result mip_filter_default_speed_lever_arm(struct mip_interface* device, /// By convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed in /// any orientation on the vehicle if the appropriate mounting transformation has been specified). /// This constraint will typically improve heading estimates for vehicles where the assumption is valid, such -/// as an automobile, particulary when GNSS coverage is intermittent. +/// as an automobile, particularly when GNSS coverage is intermittent. /// ///@{ @@ -1364,6 +2183,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1400,6 +2220,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1436,40 +2257,7 @@ 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_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); -///@} -/// -//////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetic_declination_source (0x0D,0x43) Magnetic Declination Source [C] -/// Source for magnetic declination angle, and user supplied value for manual selection. -/// -///@{ - -struct mip_filter_magnetic_declination_source_command -{ - mip_function_selector function; - mip_filter_mag_declination_source source; ///< Magnetic field declination angle source - float declination; ///< Declination angle used when 'source' is set to 'MANUAL' (radians) - -}; -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); -struct mip_filter_magnetic_declination_source_response -{ - mip_filter_mag_declination_source source; ///< Magnetic field declination angle source - float declination; ///< Declination angle used when 'source' is set to 'MANUAL' (radians) - -}; -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); - -mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_declination_source source, float declination); -mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_declination_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); ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1491,6 +2279,7 @@ void insert_mip_filter_set_initial_heading_command(struct mip_serializer* serial void extract_mip_filter_set_initial_heading_command(struct mip_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_filter.hpp b/src/mip/definitions/commands_filter.hpp index 501e46b0a..3e4b5ce68 100644 --- a/src/mip/definitions/commands_filter.hpp +++ b/src/mip/definitions/commands_filter.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -160,11 +161,18 @@ enum class FilterReferenceFrame : uint8_t LLH = 2, ///< WGS84 Latitude, longitude, and height above ellipsoid }; -enum class FilterMagDeclinationSource : uint8_t +enum class FilterMagParamSource : uint8_t { - NONE = 1, ///< Magnetic field is assumed to have an declination angle equal to zero. + NONE = 1, ///< No source. See command documentation for default behavior WMM = 2, ///< Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model. - MANUAL = 3, ///< Magnetic field is assumed to have the declination angle specified by the user. + MANUAL = 3, ///< Magnetic field is assumed to have the parameter specified by the user. +}; + +enum class FilterAdaptiveMeasurement : uint8_t +{ + DISABLED = 0, ///< No adaptive measurement + FIXED = 1, ///< Enable fixed adaptive measurement (use specified limits) + AUTO = 2, ///< Enable auto adaptive measurement }; @@ -183,17 +191,32 @@ enum class FilterMagDeclinationSource : uint8_t struct Reset { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_RESET_FILTER; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; }; void insert(Serializer& serializer, const Reset& self); void extract(Serializer& serializer, Reset& self); -CmdResult reset(C::mip_interface& device); +TypedResult reset(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -215,20 +238,35 @@ CmdResult reset(C::mip_interface& device); struct SetInitialAttitude { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SET_INITIAL_ATTITUDE; - - static const bool HAS_FUNCTION_SELECTOR = false; - float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float heading = 0; ///< [radians] + 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 + { + return std::make_tuple(roll,pitch,heading); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(heading)); + } + typedef void Response; }; void insert(Serializer& serializer, const SetInitialAttitude& self); void extract(Serializer& serializer, SetInitialAttitude& self); -CmdResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading); +TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -249,15 +287,6 @@ CmdResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, struct EstimationControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ESTIMATION_CONTROL_FLAGS; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - struct EnableFlags : Bitfield { enum _enumType : uint16_t @@ -270,6 +299,7 @@ struct EstimationControl ANTENNA_OFFSET = 0x0010, ///< AUTO_MAG_HARD_IRON = 0x0020, ///< AUTO_MAG_SOFT_IRON = 0x0040, ///< + ALL = 0x007F, }; uint16_t value = NONE; @@ -277,21 +307,81 @@ struct EstimationControl EnableFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } EnableFlags& operator=(uint16_t val) { value = val; return *this; } - EnableFlags& operator=(int val) { value = val; return *this; } + EnableFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; FunctionSelector function = static_cast(0); EnableFlags enable; ///< See above + 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 + { + return std::make_tuple(enable); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } + + static EstimationControl create_sld_all(::mip::FunctionSelector function) + { + EstimationControl cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ESTIMATION_CONTROL_FLAGS; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; EnableFlags enable; ///< See above + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } }; }; void insert(Serializer& serializer, const EstimationControl& self); @@ -300,11 +390,12 @@ void extract(Serializer& serializer, EstimationControl& self); void insert(Serializer& serializer, const EstimationControl::Response& self); void extract(Serializer& serializer, EstimationControl::Response& self); -CmdResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable); -CmdResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut); -CmdResult saveEstimationControl(C::mip_interface& device); -CmdResult loadEstimationControl(C::mip_interface& device); -CmdResult defaultEstimationControl(C::mip_interface& device); +TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable); +TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut); +TypedResult saveEstimationControl(C::mip_interface& device); +TypedResult loadEstimationControl(C::mip_interface& device); +TypedResult defaultEstimationControl(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -319,25 +410,40 @@ CmdResult defaultEstimationControl(C::mip_interface& device); struct ExternalGnssUpdate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_EXTERNAL_GNSS_UPDATE; - - static const bool HAS_FUNCTION_SELECTOR = false; - double gps_time = 0; ///< [seconds] uint16_t gps_week = 0; ///< [GPS week number, not modulus 1024] double latitude = 0; ///< [degrees] double longitude = 0; ///< [degrees] double height = 0; ///< Above WGS84 ellipsoid [meters] - float velocity[3] = {0}; ///< NED Frame [meters/second] - float pos_uncertainty[3] = {0}; ///< NED Frame, 1-sigma [meters] - float vel_uncertainty[3] = {0}; ///< NED Frame, 1-sigma [meters/second] + Vector3f velocity; ///< NED Frame [meters/second] + Vector3f pos_uncertainty; ///< NED Frame, 1-sigma [meters] + Vector3f vel_uncertainty; ///< NED Frame, 1-sigma [meters/second] + 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 + { + return std::make_tuple(gps_time,gps_week,latitude,longitude,height,velocity,pos_uncertainty,vel_uncertainty); + } + + auto as_tuple() + { + 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)); + } + typedef void Response; }; void insert(Serializer& serializer, const ExternalGnssUpdate& self); void extract(Serializer& serializer, ExternalGnssUpdate& self); -CmdResult 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); +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -360,20 +466,35 @@ CmdResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t struct ExternalHeadingUpdate { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_EXTERNAL_HEADING_UPDATE; - - static const bool HAS_FUNCTION_SELECTOR = false; - float heading = 0; ///< Bounded by +-PI [radians] float heading_uncertainty = 0; ///< 1-sigma [radians] uint8_t type = 0; ///< 1 - True, 2 - Magnetic + 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 + { + return std::make_tuple(heading,heading_uncertainty,type); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(heading),std::ref(heading_uncertainty),std::ref(type)); + } + typedef void Response; }; void insert(Serializer& serializer, const ExternalHeadingUpdate& self); void extract(Serializer& serializer, ExternalHeadingUpdate& self); -CmdResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type); +TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -400,22 +521,37 @@ CmdResult externalHeadingUpdate(C::mip_interface& device, float heading, float h struct ExternalHeadingUpdateWithTime { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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 + 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 + { + return std::make_tuple(gps_time,gps_week,heading,heading_uncertainty,type); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(gps_time),std::ref(gps_week),std::ref(heading),std::ref(heading_uncertainty),std::ref(type)); + } + typedef void Response; }; void insert(Serializer& serializer, const ExternalHeadingUpdateWithTime& self); void extract(Serializer& serializer, ExternalHeadingUpdateWithTime& self); -CmdResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type); +TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -430,15 +566,6 @@ CmdResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime struct TareOrientation { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_TARE_ORIENTATION; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - struct MipTareAxes : Bitfield { enum _enumType : uint8_t @@ -447,6 +574,7 @@ struct TareOrientation ROLL = 0x1, ///< PITCH = 0x2, ///< YAW = 0x4, ///< + ALL = 0x7, }; uint8_t value = NONE; @@ -454,21 +582,73 @@ struct TareOrientation MipTareAxes(int val) : value((uint8_t)val) {} operator uint8_t() const { return value; } MipTareAxes& operator=(uint8_t val) { value = val; return *this; } - MipTareAxes& operator=(int val) { value = val; return *this; } + MipTareAxes& operator=(int val) { value = uint8_t(val); return *this; } 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; } }; FunctionSelector function = static_cast(0); MipTareAxes axes; ///< Axes to tare + 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 + { + return std::make_tuple(axes); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(axes)); + } + + static TareOrientation create_sld_all(::mip::FunctionSelector function) + { + TareOrientation cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_TARE_ORIENTATION; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; MipTareAxes axes; ///< Axes to tare + + auto as_tuple() + { + return std::make_tuple(std::ref(axes)); + } }; }; void insert(Serializer& serializer, const TareOrientation& self); @@ -477,11 +657,96 @@ void extract(Serializer& serializer, TareOrientation& self); void insert(Serializer& serializer, const TareOrientation::Response& self); void extract(Serializer& serializer, TareOrientation::Response& self); -CmdResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes); -CmdResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut); -CmdResult saveTareOrientation(C::mip_interface& device); -CmdResult loadTareOrientation(C::mip_interface& device); -CmdResult defaultTareOrientation(C::mip_interface& device); +TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes); +TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut); +TypedResult saveTareOrientation(C::mip_interface& device); +TypedResult loadTareOrientation(C::mip_interface& device); +TypedResult defaultTareOrientation(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_vehicle_dynamics_mode (0x0D,0x10) Vehicle Dynamics Mode [CPP] +/// Controls the vehicle dynamics mode. +/// +///@{ + +struct VehicleDynamicsMode +{ + enum class DynamicsMode : uint8_t + { + PORTABLE = 1, ///< + AUTOMOTIVE = 2, ///< + AIRBORNE = 3, ///< + AIRBORNE_HIGH_G = 4, ///< + }; + + FunctionSelector function = static_cast(0); + DynamicsMode mode = static_cast(0); + + 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 + { + return std::make_tuple(mode); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(mode)); + } + + static VehicleDynamicsMode create_sld_all(::mip::FunctionSelector function) + { + VehicleDynamicsMode cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + DynamicsMode mode = static_cast(0); + + + auto as_tuple() + { + return std::make_tuple(std::ref(mode)); + } + }; +}; +void insert(Serializer& serializer, const VehicleDynamicsMode& self); +void extract(Serializer& serializer, VehicleDynamicsMode& self); + +void insert(Serializer& serializer, const VehicleDynamicsMode::Response& self); +void extract(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); +TypedResult loadVehicleDynamicsMode(C::mip_interface& device); +TypedResult defaultVehicleDynamicsMode(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -514,29 +779,62 @@ CmdResult defaultTareOrientation(C::mip_interface& device); struct SensorToVehicleRotationEuler { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_ROTATION_EULER; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] + 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 + { + return std::make_tuple(roll,pitch,yaw); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); + } + + static SensorToVehicleRotationEuler create_sld_all(::mip::FunctionSelector function) + { + SensorToVehicleRotationEuler cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_ROTATION_EULER; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); + } }; }; void insert(Serializer& serializer, const SensorToVehicleRotationEuler& self); @@ -545,11 +843,12 @@ void extract(Serializer& serializer, SensorToVehicleRotationEuler& self); void insert(Serializer& serializer, const SensorToVehicleRotationEuler::Response& self); void extract(Serializer& serializer, SensorToVehicleRotationEuler::Response& self); -CmdResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw); -CmdResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); -CmdResult saveSensorToVehicleRotationEuler(C::mip_interface& device); -CmdResult loadSensorToVehicleRotationEuler(C::mip_interface& device); -CmdResult defaultSensorToVehicleRotationEuler(C::mip_interface& device); +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); +TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device); +TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -588,25 +887,58 @@ CmdResult defaultSensorToVehicleRotationEuler(C::mip_interface& device); struct SensorToVehicleRotationDcm { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_ROTATION_DCM; + FunctionSelector function = static_cast(0); + Matrix3f dcm; - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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"; - FunctionSelector function = static_cast(0); - float dcm[9] = {0}; + 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 + { + return std::make_tuple(dcm); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(dcm)); + } + + static SensorToVehicleRotationDcm create_sld_all(::mip::FunctionSelector function) + { + SensorToVehicleRotationDcm cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_ROTATION_DCM; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Matrix3f dcm; - float dcm[9] = {0}; + auto as_tuple() + { + return std::make_tuple(std::ref(dcm)); + } }; }; void insert(Serializer& serializer, const SensorToVehicleRotationDcm& self); @@ -615,11 +947,12 @@ void extract(Serializer& serializer, SensorToVehicleRotationDcm& self); void insert(Serializer& serializer, const SensorToVehicleRotationDcm::Response& self); void extract(Serializer& serializer, SensorToVehicleRotationDcm::Response& self); -CmdResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm); -CmdResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut); -CmdResult saveSensorToVehicleRotationDcm(C::mip_interface& device); -CmdResult loadSensorToVehicleRotationDcm(C::mip_interface& device); -CmdResult defaultSensorToVehicleRotationDcm(C::mip_interface& device); +TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm); +TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut); +TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device); +TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device); +TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -657,25 +990,58 @@ CmdResult defaultSensorToVehicleRotationDcm(C::mip_interface& device); struct SensorToVehicleRotationQuaternion { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_ROTATION_QUATERNION; + FunctionSelector function = static_cast(0); + Quatf quat; - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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"; - FunctionSelector function = static_cast(0); - float quat[4] = {0}; + 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 + { + return std::make_tuple(quat); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(quat)); + } + + static SensorToVehicleRotationQuaternion create_sld_all(::mip::FunctionSelector function) + { + SensorToVehicleRotationQuaternion cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION; + 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"; - float quat[4] = {0}; + static constexpr const uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Quatf quat; + + auto as_tuple() + { + return std::make_tuple(std::ref(quat)); + } }; }; void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion& self); @@ -684,11 +1050,12 @@ void extract(Serializer& serializer, SensorToVehicleRotationQuaternion& self); void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion::Response& self); void extract(Serializer& serializer, SensorToVehicleRotationQuaternion::Response& self); -CmdResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat); -CmdResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut); -CmdResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device); -CmdResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device); -CmdResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device); +TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat); +TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut); +TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device); +TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device); +TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -707,25 +1074,58 @@ CmdResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device); struct SensorToVehicleOffset { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_OFFSET; + FunctionSelector function = static_cast(0); + Vector3f offset; ///< [meters] - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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"; - FunctionSelector function = static_cast(0); - float offset[3] = {0}; ///< [meters] + 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 + { + return std::make_tuple(offset); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } + + static SensorToVehicleOffset create_sld_all(::mip::FunctionSelector function) + { + SensorToVehicleOffset cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_OFFSET; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Vector3f offset; ///< [meters] - float offset[3] = {0}; ///< [meters] + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } }; }; void insert(Serializer& serializer, const SensorToVehicleOffset& self); @@ -734,11 +1134,12 @@ void extract(Serializer& serializer, SensorToVehicleOffset& self); void insert(Serializer& serializer, const SensorToVehicleOffset::Response& self); void extract(Serializer& serializer, SensorToVehicleOffset::Response& self); -CmdResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset); -CmdResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut); -CmdResult saveSensorToVehicleOffset(C::mip_interface& device); -CmdResult loadSensorToVehicleOffset(C::mip_interface& device); -CmdResult defaultSensorToVehicleOffset(C::mip_interface& device); +TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset); +TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut); +TypedResult saveSensorToVehicleOffset(C::mip_interface& device); +TypedResult loadSensorToVehicleOffset(C::mip_interface& device); +TypedResult defaultSensorToVehicleOffset(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -754,25 +1155,58 @@ CmdResult defaultSensorToVehicleOffset(C::mip_interface& device); struct AntennaOffset { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ANTENNA_OFFSET; + FunctionSelector function = static_cast(0); + Vector3f offset; ///< [meters] - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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"; - FunctionSelector function = static_cast(0); - float offset[3] = {0}; ///< [meters] + 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 + { + return std::make_tuple(offset); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } + + static AntennaOffset create_sld_all(::mip::FunctionSelector function) + { + AntennaOffset cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ANTENNA_OFFSET; + 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"; - float offset[3] = {0}; ///< [meters] + static constexpr const uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Vector3f offset; ///< [meters] + + auto as_tuple() + { + return std::make_tuple(std::ref(offset)); + } }; }; void insert(Serializer& serializer, const AntennaOffset& self); @@ -781,11 +1215,12 @@ void extract(Serializer& serializer, AntennaOffset& self); void insert(Serializer& serializer, const AntennaOffset::Response& self); void extract(Serializer& serializer, AntennaOffset::Response& self); -CmdResult writeAntennaOffset(C::mip_interface& device, const float* offset); -CmdResult readAntennaOffset(C::mip_interface& device, float* offsetOut); -CmdResult saveAntennaOffset(C::mip_interface& device); -CmdResult loadAntennaOffset(C::mip_interface& device); -CmdResult defaultAntennaOffset(C::mip_interface& device); +TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset); +TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut); +TypedResult saveAntennaOffset(C::mip_interface& device); +TypedResult loadAntennaOffset(C::mip_interface& device); +TypedResult defaultAntennaOffset(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -800,15 +1235,6 @@ CmdResult defaultAntennaOffset(C::mip_interface& device); struct GnssSource { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_GNSS_SOURCE_CONTROL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class Source : uint8_t { ALL_INT = 1, ///< All internal receivers @@ -820,13 +1246,55 @@ struct GnssSource FunctionSelector function = static_cast(0); Source source = static_cast(0); + 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 + { + return std::make_tuple(source); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } + + static GnssSource create_sld_all(::mip::FunctionSelector function) + { + GnssSource cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_GNSS_SOURCE_CONTROL; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; Source source = static_cast(0); + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } }; }; void insert(Serializer& serializer, const GnssSource& self); @@ -835,11 +1303,12 @@ void extract(Serializer& serializer, GnssSource& self); void insert(Serializer& serializer, const GnssSource::Response& self); void extract(Serializer& serializer, GnssSource::Response& self); -CmdResult writeGnssSource(C::mip_interface& device, GnssSource::Source source); -CmdResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut); -CmdResult saveGnssSource(C::mip_interface& device); -CmdResult loadGnssSource(C::mip_interface& device); -CmdResult defaultGnssSource(C::mip_interface& device); +TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source); +TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut); +TypedResult saveGnssSource(C::mip_interface& device); +TypedResult loadGnssSource(C::mip_interface& device); +TypedResult defaultGnssSource(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -861,20 +1330,11 @@ CmdResult defaultGnssSource(C::mip_interface& device); struct HeadingSource { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_HEADING_UPDATE_CONTROL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class Source : uint8_t { NONE = 0, ///< See note 3 MAG = 1, ///< - GNSS_VEL = 2, ///< Seen notes 1,2 + GNSS_VEL = 2, ///< See notes 1,2 EXTERNAL = 3, ///< GNSS_VEL_AND_MAG = 4, ///< GNSS_VEL_AND_EXTERNAL = 5, ///< @@ -885,13 +1345,55 @@ struct HeadingSource FunctionSelector function = static_cast(0); Source source = static_cast(0); + 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 + { + return std::make_tuple(source); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } + + static HeadingSource create_sld_all(::mip::FunctionSelector function) + { + HeadingSource cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_HEADING_UPDATE_CONTROL; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; Source source = static_cast(0); + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } }; }; void insert(Serializer& serializer, const HeadingSource& self); @@ -900,11 +1402,12 @@ void extract(Serializer& serializer, HeadingSource& self); void insert(Serializer& serializer, const HeadingSource::Response& self); void extract(Serializer& serializer, HeadingSource::Response& self); -CmdResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source); -CmdResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut); -CmdResult saveHeadingSource(C::mip_interface& device); -CmdResult loadHeadingSource(C::mip_interface& device); -CmdResult defaultHeadingSource(C::mip_interface& device); +TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source); +TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut); +TypedResult saveHeadingSource(C::mip_interface& device); +TypedResult loadHeadingSource(C::mip_interface& device); +TypedResult defaultHeadingSource(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -923,25 +1426,58 @@ CmdResult defaultHeadingSource(C::mip_interface& device); struct AutoInitControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_AUTOINIT_CONTROL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< See above + 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 + { + return std::make_tuple(enable); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } + + static AutoInitControl create_sld_all(::mip::FunctionSelector function) + { + AutoInitControl cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_AUTOINIT_CONTROL; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t enable = 0; ///< See above + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } }; }; void insert(Serializer& serializer, const AutoInitControl& self); @@ -950,200 +1486,1821 @@ void extract(Serializer& serializer, AutoInitControl& self); void insert(Serializer& serializer, const AutoInitControl::Response& self); void extract(Serializer& serializer, AutoInitControl::Response& self); -CmdResult writeAutoInitControl(C::mip_interface& device, uint8_t enable); -CmdResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut); -CmdResult saveAutoInitControl(C::mip_interface& device); -CmdResult loadAutoInitControl(C::mip_interface& device); -CmdResult defaultAutoInitControl(C::mip_interface& device); +TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable); +TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut); +TypedResult saveAutoInitControl(C::mip_interface& device); +TypedResult loadAutoInitControl(C::mip_interface& device); +TypedResult defaultAutoInitControl(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_altitude_aiding (0x0D,0x47) Altitude Aiding [CPP] -/// Altitude Aiding Control -/// -/// 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 GNSS outages. -/// -/// Possible altitude aiding selector values: +///@defgroup cpp_filter_accel_noise (0x0D,0x1A) Accel Noise [CPP] +/// Accelerometer Noise Standard Deviation /// -/// 0x00 - No altitude aiding (disable) -/// 0x01 - Enable pressure sensor aiding(1) -/// -/// 1. Pressure altitude is based on "instant sea level pressure" which is dependent on location and weather conditions and can vary by more than 40 meters. +/// Each of the noise values must be greater than 0.0. /// +/// The 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 the performance of the filter. +/// Default values provide good performance for most laboratory conditions. /// ///@{ -struct AltitudeAiding +struct AccelNoise { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ALTITUDE_AIDING_CONTROL; + FunctionSelector function = static_cast(0); + Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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"; - FunctionSelector function = static_cast(0); - uint8_t aiding_selector = 0; ///< See above + 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 + { + return std::make_tuple(noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + + static AccelNoise create_sld_all(::mip::FunctionSelector function) + { + AccelNoise cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ALTITUDE_AIDING_CONTROL; + 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"; - uint8_t aiding_selector = 0; ///< See above + 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 as_tuple() + { + return std::make_tuple(std::ref(noise)); + } }; }; -void insert(Serializer& serializer, const AltitudeAiding& self); -void extract(Serializer& serializer, AltitudeAiding& self); +void insert(Serializer& serializer, const AccelNoise& self); +void extract(Serializer& serializer, AccelNoise& self); -void insert(Serializer& serializer, const AltitudeAiding::Response& self); -void extract(Serializer& serializer, AltitudeAiding::Response& self); +void insert(Serializer& serializer, const AccelNoise::Response& self); +void extract(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); +TypedResult loadAccelNoise(C::mip_interface& device); +TypedResult defaultAccelNoise(C::mip_interface& device); -CmdResult writeAltitudeAiding(C::mip_interface& device, uint8_t aidingSelector); -CmdResult readAltitudeAiding(C::mip_interface& device, uint8_t* aidingSelectorOut); -CmdResult saveAltitudeAiding(C::mip_interface& device); -CmdResult loadAltitudeAiding(C::mip_interface& device); -CmdResult defaultAltitudeAiding(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_auto_zupt (0x0D,0x1E) Auto Zupt [CPP] -/// Zero Velocity Update -/// 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.) +///@defgroup cpp_filter_gyro_noise (0x0D,0x1B) Gyro Noise [CPP] +/// Gyroscope Noise Standard Deviation +/// +/// Each of the noise values must be greater than 0.0 +/// +/// The 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 the performance of the filter. +/// Default values provide good performance for most laboratory conditions. /// ///@{ -struct AutoZupt +struct GyroNoise { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ZUPT_CONTROL; + FunctionSelector function = static_cast(0); + Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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"; - FunctionSelector function = static_cast(0); - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - float threshold = 0; ///< [meters/second] + 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 + { + return std::make_tuple(noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + + static GyroNoise create_sld_all(::mip::FunctionSelector function) + { + GyroNoise cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ZUPT_CONTROL; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - float threshold = 0; ///< [meters/second] + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } }; }; -void insert(Serializer& serializer, const AutoZupt& self); -void extract(Serializer& serializer, AutoZupt& self); +void insert(Serializer& serializer, const GyroNoise& self); +void extract(Serializer& serializer, GyroNoise& self); -void insert(Serializer& serializer, const AutoZupt::Response& self); -void extract(Serializer& serializer, AutoZupt::Response& self); +void insert(Serializer& serializer, const GyroNoise::Response& self); +void extract(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); +TypedResult loadGyroNoise(C::mip_interface& device); +TypedResult defaultGyroNoise(C::mip_interface& device); -CmdResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold); -CmdResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); -CmdResult saveAutoZupt(C::mip_interface& device); -CmdResult loadAutoZupt(C::mip_interface& device); -CmdResult defaultAutoZupt(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_auto_angular_zupt (0x0D,0x20) Auto Angular Zupt [CPP] -/// 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.) +///@defgroup cpp_filter_accel_bias_model (0x0D,0x1C) Accel Bias Model [CPP] +/// Accelerometer Bias Model Parameters +/// +/// Noise values must be greater than 0.0 +/// /// ///@{ -struct AutoAngularZupt +struct AccelBiasModel { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ANGULAR_ZUPT_CONTROL; + FunctionSelector function = static_cast(0); + Vector3f beta; ///< Accel Bias Beta [1/second] + Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; + 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"; - FunctionSelector function = static_cast(0); - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - float threshold = 0; ///< [radians/second] + 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; - struct Response + auto as_tuple() const { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ANGULAR_ZUPT_CONTROL; - - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + return std::make_tuple(beta,noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(beta),std::ref(noise)); + } + + static AccelBiasModel create_sld_all(::mip::FunctionSelector function) + { + AccelBiasModel cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(beta),std::ref(noise)); + } + }; +}; +void insert(Serializer& serializer, const AccelBiasModel& self); +void extract(Serializer& serializer, AccelBiasModel& self); + +void insert(Serializer& serializer, const AccelBiasModel::Response& self); +void extract(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); +TypedResult loadAccelBiasModel(C::mip_interface& device); +TypedResult defaultAccelBiasModel(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_gyro_bias_model (0x0D,0x1D) Gyro Bias Model [CPP] +/// Gyroscope Bias Model Parameters +/// +/// Noise values must be greater than 0.0 +/// +/// +///@{ + +struct GyroBiasModel +{ + FunctionSelector function = static_cast(0); + Vector3f beta; ///< Gyro Bias Beta [1/second] + Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] + + 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 + { + return std::make_tuple(beta,noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(beta),std::ref(noise)); + } + + static GyroBiasModel create_sld_all(::mip::FunctionSelector function) + { + GyroBiasModel cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(beta),std::ref(noise)); + } + }; +}; +void insert(Serializer& serializer, const GyroBiasModel& self); +void extract(Serializer& serializer, GyroBiasModel& self); + +void insert(Serializer& serializer, const GyroBiasModel::Response& self); +void extract(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); +TypedResult loadGyroBiasModel(C::mip_interface& device); +TypedResult defaultGyroBiasModel(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_altitude_aiding (0x0D,0x47) Altitude Aiding [CPP] +/// 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. +/// +/// Pressure altitude is based on "instant sea level pressure" which is dependent on location and weather conditions and can vary by more than 40 meters. +/// +/// +///@{ + +struct AltitudeAiding +{ + enum class AidingSelector : uint8_t + { + NONE = 0, ///< No altitude aiding + PRESURE = 1, ///< Enable pressure sensor aiding + }; + + FunctionSelector function = static_cast(0); + AidingSelector selector = static_cast(0); ///< See above + + 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 + { + return std::make_tuple(selector); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(selector)); + } + + static AltitudeAiding create_sld_all(::mip::FunctionSelector function) + { + AltitudeAiding cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + AidingSelector selector = static_cast(0); ///< See above + + + auto as_tuple() + { + return std::make_tuple(std::ref(selector)); + } + }; +}; +void insert(Serializer& serializer, const AltitudeAiding& self); +void extract(Serializer& serializer, AltitudeAiding& self); + +void insert(Serializer& serializer, const AltitudeAiding::Response& self); +void extract(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); +TypedResult loadAltitudeAiding(C::mip_interface& device); +TypedResult defaultAltitudeAiding(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_pitch_roll_aiding (0x0D,0x4B) Pitch Roll Aiding [CPP] +/// 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. +/// +///@{ + +struct PitchRollAiding +{ + enum class AidingSource : uint8_t + { + NONE = 0, ///< No pitch/roll aiding + GRAVITY_VEC = 1, ///< Enable gravity vector aiding + }; + + FunctionSelector function = static_cast(0); + AidingSource source = static_cast(0); ///< Controls the aiding source + + 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 + { + return std::make_tuple(source); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } + + static PitchRollAiding create_sld_all(::mip::FunctionSelector function) + { + PitchRollAiding cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + AidingSource source = static_cast(0); ///< Controls the aiding source + + + auto as_tuple() + { + return std::make_tuple(std::ref(source)); + } + }; +}; +void insert(Serializer& serializer, const PitchRollAiding& self); +void extract(Serializer& serializer, PitchRollAiding& self); + +void insert(Serializer& serializer, const PitchRollAiding::Response& self); +void extract(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); +TypedResult loadPitchRollAiding(C::mip_interface& device); +TypedResult defaultPitchRollAiding(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_auto_zupt (0x0D,0x1E) Auto Zupt [CPP] +/// 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.) +/// +///@{ + +struct AutoZupt +{ + FunctionSelector function = static_cast(0); + uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + float threshold = 0; ///< [meters/second] + + 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 + { + return std::make_tuple(enable,threshold); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(threshold)); + } + + static AutoZupt create_sld_all(::mip::FunctionSelector function) + { + AutoZupt cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(threshold)); + } + }; +}; +void insert(Serializer& serializer, const AutoZupt& self); +void extract(Serializer& serializer, AutoZupt& self); + +void insert(Serializer& serializer, const AutoZupt::Response& self); +void extract(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); +TypedResult loadAutoZupt(C::mip_interface& device); +TypedResult defaultAutoZupt(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_auto_angular_zupt (0x0D,0x20) Auto Angular Zupt [CPP] +/// 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.) +/// +///@{ + +struct AutoAngularZupt +{ + FunctionSelector function = static_cast(0); + uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + float threshold = 0; ///< [radians/second] + + 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 + { + return std::make_tuple(enable,threshold); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(threshold)); + } + + static AutoAngularZupt create_sld_all(::mip::FunctionSelector function) + { + AutoAngularZupt cmd; + cmd.function = function; + return cmd; + } + + 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; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(threshold)); + } + }; +}; +void insert(Serializer& serializer, const AutoAngularZupt& self); +void extract(Serializer& serializer, AutoAngularZupt& self); + +void insert(Serializer& serializer, const AutoAngularZupt::Response& self); +void extract(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); +TypedResult loadAutoAngularZupt(C::mip_interface& device); +TypedResult defaultAutoAngularZupt(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_commanded_zupt (0x0D,0x22) Commanded Zupt [CPP] +/// Please see the device user manual for the maximum rate of this message. +/// +///@{ + +struct CommandedZupt +{ + + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; +}; +void insert(Serializer& serializer, const CommandedZupt& self); +void extract(Serializer& serializer, CommandedZupt& self); + +TypedResult commandedZupt(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_commanded_angular_zupt (0x0D,0x23) Commanded Angular Zupt [CPP] +/// Please see the device user manual for the maximum rate of this message. +/// +///@{ + +struct CommandedAngularZupt +{ + + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; +}; +void insert(Serializer& serializer, const CommandedAngularZupt& self); +void extract(Serializer& serializer, CommandedAngularZupt& self); + +TypedResult commandedAngularZupt(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_mag_capture_auto_cal (0x0D,0x27) Mag Capture Auto Cal [CPP] +/// 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. +/// +///@{ + +struct MagCaptureAutoCal +{ + FunctionSelector function = static_cast(0); + + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } + + static MagCaptureAutoCal create_sld_all(::mip::FunctionSelector function) + { + MagCaptureAutoCal cmd; + cmd.function = function; + return cmd; + } + + typedef void Response; +}; +void insert(Serializer& serializer, const MagCaptureAutoCal& self); +void extract(Serializer& serializer, MagCaptureAutoCal& self); + +TypedResult writeMagCaptureAutoCal(C::mip_interface& device); +TypedResult saveMagCaptureAutoCal(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_gravity_noise (0x0D,0x28) Gravity Noise [CPP] +/// 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 +/// +/// The 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. +/// Default values provide good performance for most laboratory conditions. +/// +///@{ + +struct GravityNoise +{ + FunctionSelector function = static_cast(0); + Vector3f noise; ///< Gravity Noise 1-sigma [gauss] + + 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 + { + return std::make_tuple(noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + + static GravityNoise create_sld_all(::mip::FunctionSelector function) + { + GravityNoise cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Vector3f noise; ///< Gravity Noise 1-sigma [gauss] + + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + }; +}; +void insert(Serializer& serializer, const GravityNoise& self); +void extract(Serializer& serializer, GravityNoise& self); + +void insert(Serializer& serializer, const GravityNoise::Response& self); +void extract(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); +TypedResult loadGravityNoise(C::mip_interface& device); +TypedResult defaultGravityNoise(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_pressure_altitude_noise (0x0D,0x29) Pressure Altitude Noise [CPP] +/// 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 +/// +/// This noise value represents pressure altitude model noise in the Estimation Filter. +/// A 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. +/// +///@{ + +struct PressureAltitudeNoise +{ + FunctionSelector function = static_cast(0); + float noise = 0; ///< Pressure Altitude Noise 1-sigma [m] + + 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 + { + return std::make_tuple(noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + + static PressureAltitudeNoise create_sld_all(::mip::FunctionSelector function) + { + PressureAltitudeNoise cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + float noise = 0; ///< Pressure Altitude Noise 1-sigma [m] + + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + }; +}; +void insert(Serializer& serializer, const PressureAltitudeNoise& self); +void extract(Serializer& serializer, PressureAltitudeNoise& self); + +void insert(Serializer& serializer, const PressureAltitudeNoise::Response& self); +void extract(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); +TypedResult loadPressureAltitudeNoise(C::mip_interface& device); +TypedResult defaultPressureAltitudeNoise(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_hard_iron_offset_noise (0x0D,0x2B) Hard Iron Offset Noise [CPP] +/// 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. +/// +/// Noise values must be greater than 0.0 +/// +/// The noise values represent process noise in the Estimation Filter. +/// Changing 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. +/// +///@{ + +struct HardIronOffsetNoise +{ + FunctionSelector function = static_cast(0); + Vector3f noise; ///< Hard Iron Offset Noise 1-sigma [gauss] + + 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 + { + return std::make_tuple(noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + + static HardIronOffsetNoise create_sld_all(::mip::FunctionSelector function) + { + HardIronOffsetNoise cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Vector3f noise; ///< Hard Iron Offset Noise 1-sigma [gauss] + + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + }; +}; +void insert(Serializer& serializer, const HardIronOffsetNoise& self); +void extract(Serializer& serializer, HardIronOffsetNoise& self); + +void insert(Serializer& serializer, const HardIronOffsetNoise::Response& self); +void extract(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); +TypedResult loadHardIronOffsetNoise(C::mip_interface& device); +TypedResult defaultHardIronOffsetNoise(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_soft_iron_matrix_noise (0x0D,0x2C) Soft Iron Matrix Noise [CPP] +/// Set the expected soft iron matrix noise 1-sigma values. +/// This function can be used to tune the filter performance in the target application. +/// +/// Noise values must be greater than 0.0 +/// +/// The 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 the performance of the filter. Default values provide good performance for most laboratory conditions. +/// +///@{ + +struct SoftIronMatrixNoise +{ + FunctionSelector function = static_cast(0); + Matrix3f noise; ///< Soft Iron Matrix Noise 1-sigma [dimensionless] + + 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 + { + return std::make_tuple(noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + + static SoftIronMatrixNoise create_sld_all(::mip::FunctionSelector function) + { + SoftIronMatrixNoise cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Matrix3f noise; ///< Soft Iron Matrix Noise 1-sigma [dimensionless] + + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + }; +}; +void insert(Serializer& serializer, const SoftIronMatrixNoise& self); +void extract(Serializer& serializer, SoftIronMatrixNoise& self); + +void insert(Serializer& serializer, const SoftIronMatrixNoise::Response& self); +void extract(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); +TypedResult loadSoftIronMatrixNoise(C::mip_interface& device); +TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_mag_noise (0x0D,0x42) Mag Noise [CPP] +/// Set the expected magnetometer noise 1-sigma values. +/// This function can be used to tune the filter performance in the target application. +/// +/// Noise values must be greater than 0.0 (gauss) +/// +/// The 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 the performance of the filter. Default values provide good performance for most laboratory conditions +/// +///@{ + +struct MagNoise +{ + FunctionSelector function = static_cast(0); + Vector3f noise; ///< Mag Noise 1-sigma [gauss] + + 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 + { + return std::make_tuple(noise); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + + static MagNoise create_sld_all(::mip::FunctionSelector function) + { + MagNoise cmd; + cmd.function = function; + return cmd; + } + + 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_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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + Vector3f noise; ///< Mag Noise 1-sigma [gauss] + + + auto as_tuple() + { + return std::make_tuple(std::ref(noise)); + } + }; +}; +void insert(Serializer& serializer, const MagNoise& self); +void extract(Serializer& serializer, MagNoise& self); + +void insert(Serializer& serializer, const MagNoise::Response& self); +void extract(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); +TypedResult loadMagNoise(C::mip_interface& device); +TypedResult defaultMagNoise(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_inclination_source (0x0D,0x4C) Inclination Source [CPP] +/// 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. +/// Having 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. +/// +/// +///@{ + +struct InclinationSource +{ + FunctionSelector function = static_cast(0); + FilterMagParamSource source = static_cast(0); ///< Inclination Source + float inclination = 0; ///< Inclination angle [radians] (only required if source = MANUAL) + + 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 + { + return std::make_tuple(source,inclination); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(inclination)); + } + + static InclinationSource create_sld_all(::mip::FunctionSelector function) + { + InclinationSource cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(inclination)); + } + }; +}; +void insert(Serializer& serializer, const InclinationSource& self); +void extract(Serializer& serializer, InclinationSource& self); + +void insert(Serializer& serializer, const InclinationSource::Response& self); +void extract(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); +TypedResult loadInclinationSource(C::mip_interface& device); +TypedResult defaultInclinationSource(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_magnetic_declination_source (0x0D,0x43) Magnetic Declination Source [CPP] +/// 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. +/// Having 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. +/// +/// +///@{ + +struct MagneticDeclinationSource +{ + 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) + + 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 + { + return std::make_tuple(source,declination); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(declination)); + } + + static MagneticDeclinationSource create_sld_all(::mip::FunctionSelector function) + { + MagneticDeclinationSource cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(declination)); + } + }; +}; +void insert(Serializer& serializer, const MagneticDeclinationSource& self); +void extract(Serializer& serializer, MagneticDeclinationSource& self); + +void insert(Serializer& serializer, const MagneticDeclinationSource::Response& self); +void extract(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); +TypedResult loadMagneticDeclinationSource(C::mip_interface& device); +TypedResult defaultMagneticDeclinationSource(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_mag_field_magnitude_source (0x0D,0x4D) Mag Field Magnitude Source [CPP] +/// Set/Get the local magnetic field magnitude source. +/// +/// This is used to specify the local magnitude of the earth's magnetic field. +/// Having 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. +/// +///@{ + +struct MagFieldMagnitudeSource +{ + FunctionSelector function = static_cast(0); + FilterMagParamSource source = static_cast(0); ///< Magnetic Field Magnitude Source + float magnitude = 0; ///< Magnitude [gauss] (only required if source = MANUAL) + + 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 + { + return std::make_tuple(source,magnitude); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(magnitude)); + } + + static MagFieldMagnitudeSource create_sld_all(::mip::FunctionSelector function) + { + MagFieldMagnitudeSource cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(magnitude)); + } + }; +}; +void insert(Serializer& serializer, const MagFieldMagnitudeSource& self); +void extract(Serializer& serializer, MagFieldMagnitudeSource& self); + +void insert(Serializer& serializer, const MagFieldMagnitudeSource::Response& self); +void extract(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); +TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device); +TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_reference_position (0x0D,0x26) Reference Position [CPP] +/// 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. +/// +/// +///@{ + +struct ReferencePosition +{ + FunctionSelector function = static_cast(0); + bool enable = 0; ///< enable/disable + double latitude = 0; ///< [degrees] + double longitude = 0; ///< [degrees] + double altitude = 0; ///< [meters] + + 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 + { + return std::make_tuple(enable,latitude,longitude,altitude); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(latitude),std::ref(longitude),std::ref(altitude)); + } + + static ReferencePosition create_sld_all(::mip::FunctionSelector function) + { + ReferencePosition cmd; + cmd.function = function; + return cmd; + } + + 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_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 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 as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(latitude),std::ref(longitude),std::ref(altitude)); + } + }; +}; +void insert(Serializer& serializer, const ReferencePosition& self); +void extract(Serializer& serializer, ReferencePosition& self); + +void insert(Serializer& serializer, const ReferencePosition::Response& self); +void extract(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); +TypedResult loadReferencePosition(C::mip_interface& device); +TypedResult defaultReferencePosition(C::mip_interface& device); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_accel_magnitude_error_adaptive_measurement (0x0D,0x44) Accel Magnitude Error Adaptive Measurement [CPP] +/// Enable or disable the gravity magnitude error adaptive measurement. +/// This function can be used to tune the filter performance in the target application +/// +/// Pick values that give you the least occurrence of invalid EF attitude output. +/// The default values are good for standard low dynamics applications. +/// Increase values for higher dynamic conditions, lower values for lower dynamic. +/// Too low a value will result in excessive heading errors. +/// Higher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc. +/// +/// 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. +/// Instead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality. +/// +/// +///@{ + +struct AccelMagnitudeErrorAdaptiveMeasurement +{ + FunctionSelector function = static_cast(0); + 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] + float high_limit = 0; ///< [meters/second^2] + float low_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + + 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 + { + return std::make_tuple(adaptive_measurement,frequency,low_limit,high_limit,low_limit_uncertainty,high_limit_uncertainty,minimum_uncertainty); + } + + auto as_tuple() + { + 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)); + } + + static AccelMagnitudeErrorAdaptiveMeasurement create_sld_all(::mip::FunctionSelector function) + { + AccelMagnitudeErrorAdaptiveMeasurement cmd; + cmd.function = function; + return cmd; + } + + 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; + 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] + float high_limit = 0; ///< [meters/second^2] + float low_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + + + auto as_tuple() + { + 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)); + } }; }; -void insert(Serializer& serializer, const AutoAngularZupt& self); -void extract(Serializer& serializer, AutoAngularZupt& self); +void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self); +void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self); -void insert(Serializer& serializer, const AutoAngularZupt::Response& self); -void extract(Serializer& serializer, AutoAngularZupt::Response& self); +void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self); +void extract(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); +TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device); +TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device); -CmdResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold); -CmdResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); -CmdResult saveAutoAngularZupt(C::mip_interface& device); -CmdResult loadAutoAngularZupt(C::mip_interface& device); -CmdResult defaultAutoAngularZupt(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_commanded_zupt (0x0D,0x22) Commanded Zupt [CPP] -/// Commanded Zero Velocity Update -/// Please see the device user manual for the maximum rate of this message. +///@defgroup cpp_filter_mag_magnitude_error_adaptive_measurement (0x0D,0x45) Mag Magnitude Error Adaptive Measurement [CPP] +/// 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). +/// +/// Pick values that give you the least occurrence of invalid EF attitude output. +/// The default values are good for standard low dynamics applications. +/// Increase values for higher dynamic conditions, lower values for lower dynamic. +/// Too low a value will result in excessive heading errors. +/// Higher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc. +/// /// ///@{ -struct CommandedZupt +struct MagMagnitudeErrorAdaptiveMeasurement { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_COMMANDED_ZUPT; + FunctionSelector function = static_cast(0); + 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] + float high_limit = 0; ///< [meters/second^2] + float low_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + + 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 + { + return std::make_tuple(adaptive_measurement,frequency,low_limit,high_limit,low_limit_uncertainty,high_limit_uncertainty,minimum_uncertainty); + } - static const bool HAS_FUNCTION_SELECTOR = false; + auto as_tuple() + { + 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)); + } + static MagMagnitudeErrorAdaptiveMeasurement create_sld_all(::mip::FunctionSelector function) + { + MagMagnitudeErrorAdaptiveMeasurement cmd; + cmd.function = function; + return cmd; + } + 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; + 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] + float high_limit = 0; ///< [meters/second^2] + float low_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] + float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + + + auto as_tuple() + { + 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)); + } + }; }; -void insert(Serializer& serializer, const CommandedZupt& self); -void extract(Serializer& serializer, CommandedZupt& self); +void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self); +void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self); + +void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self); +void extract(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); +TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device); +TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device); -CmdResult commandedZupt(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_commanded_angular_zupt (0x0D,0x23) Commanded Angular Zupt [CPP] -/// Commanded Zero Angular Rate Update -/// Please see the device user manual for the maximum rate of this message. +///@defgroup cpp_filter_mag_dip_angle_error_adaptive_measurement (0x0D,0x46) Mag Dip Angle Error Adaptive Measurement [CPP] +/// Enable or disable the magnetometer dip angle error adaptive measurement. +/// This function can be used to tune the filter performance in the target application +/// +/// Pick values that give you the least occurrence of invalid EF attitude output. +/// The default values are good for standard low dynamics applications. +/// Increase values for higher dynamic conditions, lower values for lower dynamic. +/// Too low a value will result in excessive heading errors. +/// Higher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc. +/// +/// The magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected. +/// /// ///@{ -struct CommandedAngularZupt +struct MagDipAngleErrorAdaptiveMeasurement { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_COMMANDED_ANGULAR_ZUPT; + FunctionSelector function = static_cast(0); + 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] + + 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 + { + return std::make_tuple(enable,frequency,high_limit,high_limit_uncertainty,minimum_uncertainty); + } - static const bool HAS_FUNCTION_SELECTOR = false; + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(frequency),std::ref(high_limit),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); + } + static MagDipAngleErrorAdaptiveMeasurement create_sld_all(::mip::FunctionSelector function) + { + MagDipAngleErrorAdaptiveMeasurement cmd; + cmd.function = function; + return cmd; + } + 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; + 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] + + + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(frequency),std::ref(high_limit),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); + } + }; }; -void insert(Serializer& serializer, const CommandedAngularZupt& self); -void extract(Serializer& serializer, CommandedAngularZupt& self); +void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self); +void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self); + +void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self); +void extract(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); +TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device); +TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device); -CmdResult commandedAngularZupt(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1156,38 +3313,75 @@ CmdResult commandedAngularZupt(C::mip_interface& device); struct AidingMeasurementEnable { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_AIDING_MEASUREMENT_ENABLE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class AidingSource : uint16_t { - GNSS_POS_VEL = 0, ///< GNSS Position and Velocity - GNSS_HEADING = 1, ///< GNSS Heading (dual antenna) - ALTIMETER = 2, ///< Altimeter - SPEED = 3, ///< Speed sensor / Odometer - MAGNETOMETER = 4, ///< Magnetometer - EXTERNAL_HEADING = 5, ///< External heading input - ALL = 65535, ///< Save/load/reset all options + GNSS_POS_VEL = 0, ///< GNSS Position and Velocity + GNSS_HEADING = 1, ///< GNSS Heading (dual antenna) + ALTIMETER = 2, ///< Pressure altimeter (built-in sensor) + SPEED = 3, ///< Speed sensor / Odometer + MAGNETOMETER = 4, ///< Magnetometer (built-in sensor) + 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 + ALL = 65535, ///< Save/load/reset all options }; FunctionSelector function = static_cast(0); AidingSource aiding_source = static_cast(0); ///< Aiding measurement source - bool enable = 0; ///< Controls the aiding sorce + bool enable = 0; ///< Controls the aiding source + + 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 + { + return std::make_tuple(aiding_source,enable); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(aiding_source),std::ref(enable)); + } + + static AidingMeasurementEnable create_sld_all(::mip::FunctionSelector function) + { + AidingMeasurementEnable cmd; + cmd.function = function; + cmd.aiding_source = ::mip::commands_filter::AidingMeasurementEnable::AidingSource::ALL; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_AIDING_MEASUREMENT_ENABLE; + 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 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 sorce + bool enable = 0; ///< Controls the aiding source + + auto as_tuple() + { + return std::make_tuple(std::ref(aiding_source),std::ref(enable)); + } }; }; void insert(Serializer& serializer, const AidingMeasurementEnable& self); @@ -1196,11 +3390,12 @@ void extract(Serializer& serializer, AidingMeasurementEnable& self); void insert(Serializer& serializer, const AidingMeasurementEnable::Response& self); void extract(Serializer& serializer, AidingMeasurementEnable::Response& self); -CmdResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable); -CmdResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut); -CmdResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource); -CmdResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource); -CmdResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource); +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); +TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource); +TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1213,17 +3408,32 @@ CmdResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasure struct Run { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_RUN; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; }; void insert(Serializer& serializer, const Run& self); void extract(Serializer& serializer, Run& self); -CmdResult run(C::mip_interface& device); +TypedResult run(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1236,29 +3446,62 @@ CmdResult run(C::mip_interface& device); struct KinematicConstraint { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_KINEMATIC_CONSTRAINT; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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). + 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 + { + return std::make_tuple(acceleration_constraint_selection,velocity_constraint_selection,angular_constraint_selection); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(acceleration_constraint_selection),std::ref(velocity_constraint_selection),std::ref(angular_constraint_selection)); + } + + static KinematicConstraint create_sld_all(::mip::FunctionSelector function) + { + KinematicConstraint cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_KINEMATIC_CONSTRAINT; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(acceleration_constraint_selection),std::ref(velocity_constraint_selection),std::ref(angular_constraint_selection)); + } }; }; void insert(Serializer& serializer, const KinematicConstraint& self); @@ -1267,11 +3510,12 @@ void extract(Serializer& serializer, KinematicConstraint& self); void insert(Serializer& serializer, const KinematicConstraint::Response& self); void extract(Serializer& serializer, KinematicConstraint::Response& self); -CmdResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection); -CmdResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut); -CmdResult saveKinematicConstraint(C::mip_interface& device); -CmdResult loadKinematicConstraint(C::mip_interface& device); -CmdResult defaultKinematicConstraint(C::mip_interface& device); +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); +TypedResult loadKinematicConstraint(C::mip_interface& device); +TypedResult defaultKinematicConstraint(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1286,15 +3530,6 @@ CmdResult defaultKinematicConstraint(C::mip_interface& device); struct InitializationConfiguration { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_INITIALIZATION_CONFIGURATION; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - struct AlignmentSelector : Bitfield { enum _enumType : uint8_t @@ -1302,7 +3537,9 @@ struct InitializationConfiguration NONE = 0x00, DUAL_ANTENNA = 0x01, ///< Dual-antenna GNSS alignment KINEMATIC = 0x02, ///< GNSS kinematic alignment (GNSS velocity determines initial heading) - MAGNETOMETER = 0x04, ///< Magnetometer heading alignment + MAGNETOMETER = 0x04, ///< Magnetometer heading alignment (Internal magnetometer determines initial heading) + EXTERNAL = 0x08, ///< External heading alignment (External heading input determines heading) + ALL = 0x0F, }; uint8_t value = NONE; @@ -1310,9 +3547,21 @@ struct InitializationConfiguration AlignmentSelector(int val) : value((uint8_t)val) {} operator uint8_t() const { return value; } AlignmentSelector& operator=(uint8_t val) { value = val; return *this; } - AlignmentSelector& operator=(int val) { value = val; return *this; } + AlignmentSelector& operator=(int val) { value = uint8_t(val); return *this; } 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 @@ -1330,25 +3579,67 @@ struct InitializationConfiguration float initial_heading = 0; ///< User-specified initial platform heading (degrees). float initial_pitch = 0; ///< User-specified initial platform pitch (degrees) float initial_roll = 0; ///< User-specified initial platform roll (degrees) - float initial_position[3] = {0}; ///< User-specified initial platform position (units determined by reference frame selector, see note.) - float initial_velocity[3] = {0}; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) + Vector3f initial_position; ///< User-specified initial platform position (units determined by reference frame selector, see note.) + 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 + 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 + { + 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() + { + 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)); + } + + static InitializationConfiguration create_sld_all(::mip::FunctionSelector function) + { + InitializationConfiguration cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_INITIALIZATION_CONFIGURATION; + 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; 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:
float initial_heading = 0; ///< User-specified initial platform heading (degrees). float initial_pitch = 0; ///< User-specified initial platform pitch (degrees) float initial_roll = 0; ///< User-specified initial platform roll (degrees) - float initial_position[3] = {0}; ///< User-specified initial platform position (units determined by reference frame selector, see note.) - float initial_velocity[3] = {0}; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) + Vector3f initial_position; ///< User-specified initial platform position (units determined by reference frame selector, see note.) + 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 + + auto as_tuple() + { + 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)); + } }; }; void insert(Serializer& serializer, const InitializationConfiguration& self); @@ -1357,11 +3648,12 @@ void extract(Serializer& serializer, InitializationConfiguration& self); void insert(Serializer& serializer, const InitializationConfiguration::Response& self); void extract(Serializer& serializer, InitializationConfiguration::Response& self); -CmdResult 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); -CmdResult 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); -CmdResult saveInitializationConfiguration(C::mip_interface& device); -CmdResult loadInitializationConfiguration(C::mip_interface& device); -CmdResult defaultInitializationConfiguration(C::mip_interface& device); +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); +TypedResult loadInitializationConfiguration(C::mip_interface& device); +TypedResult defaultInitializationConfiguration(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1372,27 +3664,60 @@ CmdResult defaultInitializationConfiguration(C::mip_interface& device); struct AdaptiveFilterOptions { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ADAPTIVE_FILTER_OPTIONS; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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) + 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 + { + return std::make_tuple(level,time_limit); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(level),std::ref(time_limit)); + } + + static AdaptiveFilterOptions create_sld_all(::mip::FunctionSelector function) + { + AdaptiveFilterOptions cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ADAPTIVE_FILTER_OPTIONS; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(level),std::ref(time_limit)); + } }; }; void insert(Serializer& serializer, const AdaptiveFilterOptions& self); @@ -1401,11 +3726,12 @@ void extract(Serializer& serializer, AdaptiveFilterOptions& self); void insert(Serializer& serializer, const AdaptiveFilterOptions::Response& self); void extract(Serializer& serializer, AdaptiveFilterOptions::Response& self); -CmdResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit); -CmdResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut); -CmdResult saveAdaptiveFilterOptions(C::mip_interface& device); -CmdResult loadAdaptiveFilterOptions(C::mip_interface& device); -CmdResult defaultAdaptiveFilterOptions(C::mip_interface& device); +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); +TypedResult loadAdaptiveFilterOptions(C::mip_interface& device); +TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1413,32 +3739,67 @@ CmdResult defaultAdaptiveFilterOptions(C::mip_interface& device); /// Set the antenna lever arm. /// /// This command works with devices that utilize multiple antennas. +///

Offset Limit: 10 m magnitude (default) /// ///@{ struct MultiAntennaOffset { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_MULTI_ANTENNA_OFFSET; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t receiver_id = 0; ///< Receiver: 1, 2, etc... - float antenna_offset[3] = {0}; ///< Antenna lever arm offset vector in the vehicle frame (m) + Vector3f antenna_offset; ///< Antenna lever arm offset vector in the vehicle frame (m) + + 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 + { + return std::make_tuple(receiver_id,antenna_offset); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(receiver_id),std::ref(antenna_offset)); + } + + static MultiAntennaOffset create_sld_all(::mip::FunctionSelector function) + { + MultiAntennaOffset cmd; + cmd.function = function; + cmd.receiver_id = 0; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MULTI_ANTENNA_OFFSET; + 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 uint32_t ECHOED_PARAMS = 0x0001; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t receiver_id = 0; - float antenna_offset[3] = {0}; + Vector3f antenna_offset; + + auto as_tuple() + { + return std::make_tuple(std::ref(receiver_id),std::ref(antenna_offset)); + } }; }; void insert(Serializer& serializer, const MultiAntennaOffset& self); @@ -1447,11 +3808,12 @@ void extract(Serializer& serializer, MultiAntennaOffset& self); void insert(Serializer& serializer, const MultiAntennaOffset::Response& self); void extract(Serializer& serializer, MultiAntennaOffset::Response& self); -CmdResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset); -CmdResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut); -CmdResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId); -CmdResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId); -CmdResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId); +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); +TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId); +TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1462,29 +3824,62 @@ CmdResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId struct RelPosConfiguration { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_REL_POS_CONFIGURATION; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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 - double reference_coordinates[3] = {0}; ///< reference coordinates, units determined by source selection + Vector3d reference_coordinates; ///< reference coordinates, units determined by source selection + + 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 + { + return std::make_tuple(source,reference_frame_selector,reference_coordinates); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(reference_frame_selector),std::ref(reference_coordinates)); + } + + static RelPosConfiguration create_sld_all(::mip::FunctionSelector function) + { + RelPosConfiguration cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_REL_POS_CONFIGURATION; + 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 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 - double reference_coordinates[3] = {0}; ///< reference coordinates, units determined by source selection + Vector3d reference_coordinates; ///< reference coordinates, units determined by source selection + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(reference_frame_selector),std::ref(reference_coordinates)); + } }; }; void insert(Serializer& serializer, const RelPosConfiguration& self); @@ -1493,11 +3888,12 @@ void extract(Serializer& serializer, RelPosConfiguration& self); void insert(Serializer& serializer, const RelPosConfiguration::Response& self); void extract(Serializer& serializer, RelPosConfiguration::Response& self); -CmdResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates); -CmdResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut); -CmdResult saveRelPosConfiguration(C::mip_interface& device); -CmdResult loadRelPosConfiguration(C::mip_interface& device); -CmdResult defaultRelPosConfiguration(C::mip_interface& device); +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); +TypedResult loadRelPosConfiguration(C::mip_interface& device); +TypedResult defaultRelPosConfiguration(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1506,22 +3902,15 @@ CmdResult defaultRelPosConfiguration(C::mip_interface& device); /// 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, /// and a velocity offset that depends on vehicle attitude and angular rate. -/// 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. -/// 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) +///
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. +///

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) +///

Offset Limits +///
Reference Point VEH (1): 10 m magnitude (default) /// ///@{ struct RefPointLeverArm { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_REF_POINT_LEVER_ARM; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class ReferencePointSelector : uint8_t { VEH = 1, ///< Defines the origin of the vehicle @@ -1529,16 +3918,58 @@ struct RefPointLeverArm FunctionSelector function = static_cast(0); ReferencePointSelector ref_point_sel = static_cast(0); ///< Reserved, must be 1 - float lever_arm_offset[3] = {0}; ///< [m] Lever arm offset vector in the vehicle's reference frame. + Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + + 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 + { + return std::make_tuple(ref_point_sel,lever_arm_offset); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(ref_point_sel),std::ref(lever_arm_offset)); + } + + static RefPointLeverArm create_sld_all(::mip::FunctionSelector function) + { + RefPointLeverArm cmd; + cmd.function = function; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_REF_POINT_LEVER_ARM; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; ReferencePointSelector ref_point_sel = static_cast(0); ///< Reserved, must be 1 - float lever_arm_offset[3] = {0}; ///< [m] Lever arm offset vector in the vehicle's reference frame. + Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + + auto as_tuple() + { + return std::make_tuple(std::ref(ref_point_sel),std::ref(lever_arm_offset)); + } }; }; void insert(Serializer& serializer, const RefPointLeverArm& self); @@ -1547,11 +3978,12 @@ void extract(Serializer& serializer, RefPointLeverArm& self); void insert(Serializer& serializer, const RefPointLeverArm::Response& self); void extract(Serializer& serializer, RefPointLeverArm::Response& self); -CmdResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset); -CmdResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut); -CmdResult saveRefPointLeverArm(C::mip_interface& device); -CmdResult loadRefPointLeverArm(C::mip_interface& device); -CmdResult defaultRefPointLeverArm(C::mip_interface& device); +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); +TypedResult loadRefPointLeverArm(C::mip_interface& device); +TypedResult defaultRefPointLeverArm(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1564,21 +3996,36 @@ CmdResult defaultRefPointLeverArm(C::mip_interface& device); struct SpeedMeasurement { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SPEED_MEASUREMENT; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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] + 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 + { + return std::make_tuple(source,time_of_week,speed,speed_uncertainty); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(time_of_week),std::ref(speed),std::ref(speed_uncertainty)); + } + typedef void Response; }; void insert(Serializer& serializer, const SpeedMeasurement& self); void extract(Serializer& serializer, SpeedMeasurement& self); -CmdResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty); +TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1595,27 +4042,61 @@ CmdResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeO struct SpeedLeverArm { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SPEED_LEVER_ARM; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t source = 0; ///< Reserved, must be 1. - float lever_arm_offset[3] = {0}; ///< [m] Lever arm offset vector in the vehicle's reference frame. + Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + + 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 + { + return std::make_tuple(source,lever_arm_offset); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(lever_arm_offset)); + } + + static SpeedLeverArm create_sld_all(::mip::FunctionSelector function) + { + SpeedLeverArm cmd; + cmd.function = function; + cmd.source = 0; + return cmd; + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SPEED_LEVER_ARM; + 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 uint32_t ECHOED_PARAMS = 0x0001; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t source = 0; ///< Reserved, must be 1. - float lever_arm_offset[3] = {0}; ///< [m] Lever arm offset vector in the vehicle's reference frame. + Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + + auto as_tuple() + { + return std::make_tuple(std::ref(source),std::ref(lever_arm_offset)); + } }; }; void insert(Serializer& serializer, const SpeedLeverArm& self); @@ -1624,11 +4105,12 @@ void extract(Serializer& serializer, SpeedLeverArm& self); void insert(Serializer& serializer, const SpeedLeverArm::Response& self); void extract(Serializer& serializer, SpeedLeverArm::Response& self); -CmdResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset); -CmdResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut); -CmdResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source); -CmdResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source); -CmdResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source); +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); +TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source); +TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1639,31 +4121,64 @@ CmdResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source); /// By convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed in /// any orientation on the vehicle if the appropriate mounting transformation has been specified). /// This constraint will typically improve heading estimates for vehicles where the assumption is valid, such -/// as an automobile, particulary when GNSS coverage is intermittent. +/// as an automobile, particularly when GNSS coverage is intermittent. /// ///@{ struct WheeledVehicleConstraintControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_VEHICLE_CONSTRAINT_CONTROL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + 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 + { + return std::make_tuple(enable); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } + + static WheeledVehicleConstraintControl create_sld_all(::mip::FunctionSelector function) + { + WheeledVehicleConstraintControl cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_VEHICLE_CONSTRAINT_CONTROL; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } }; }; void insert(Serializer& serializer, const WheeledVehicleConstraintControl& self); @@ -1672,11 +4187,12 @@ void extract(Serializer& serializer, WheeledVehicleConstraintControl& self); void insert(Serializer& serializer, const WheeledVehicleConstraintControl::Response& self); void extract(Serializer& serializer, WheeledVehicleConstraintControl::Response& self); -CmdResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable); -CmdResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut); -CmdResult saveWheeledVehicleConstraintControl(C::mip_interface& device); -CmdResult loadWheeledVehicleConstraintControl(C::mip_interface& device); -CmdResult defaultWheeledVehicleConstraintControl(C::mip_interface& device); +TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable); +TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut); +TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device); +TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device); +TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1691,25 +4207,58 @@ CmdResult defaultWheeledVehicleConstraintControl(C::mip_interface& device); struct VerticalGyroConstraintControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_GYRO_CONSTRAINT_CONTROL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + 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 + { + return std::make_tuple(enable); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } + + static VerticalGyroConstraintControl create_sld_all(::mip::FunctionSelector function) + { + VerticalGyroConstraintControl cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_GYRO_CONSTRAINT_CONTROL; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + + auto as_tuple() + { + return std::make_tuple(std::ref(enable)); + } }; }; void insert(Serializer& serializer, const VerticalGyroConstraintControl& self); @@ -1718,11 +4267,12 @@ void extract(Serializer& serializer, VerticalGyroConstraintControl& self); void insert(Serializer& serializer, const VerticalGyroConstraintControl::Response& self); void extract(Serializer& serializer, VerticalGyroConstraintControl::Response& self); -CmdResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable); -CmdResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut); -CmdResult saveVerticalGyroConstraintControl(C::mip_interface& device); -CmdResult loadVerticalGyroConstraintControl(C::mip_interface& device); -CmdResult defaultVerticalGyroConstraintControl(C::mip_interface& device); +TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable); +TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut); +TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device); +TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device); +TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1735,27 +4285,60 @@ CmdResult defaultVerticalGyroConstraintControl(C::mip_interface& device); struct GnssAntennaCalControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ANTENNA_CALIBRATION_CONTROL; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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. + 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 + { + return std::make_tuple(enable,max_offset); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(max_offset)); + } + + static GnssAntennaCalControl create_sld_all(::mip::FunctionSelector function) + { + GnssAntennaCalControl cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ANTENNA_CALIBRATION_CONTROL; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(max_offset)); + } }; }; void insert(Serializer& serializer, const GnssAntennaCalControl& self); @@ -1764,55 +4347,12 @@ void extract(Serializer& serializer, GnssAntennaCalControl& self); void insert(Serializer& serializer, const GnssAntennaCalControl::Response& self); void extract(Serializer& serializer, GnssAntennaCalControl::Response& self); -CmdResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset); -CmdResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut); -CmdResult saveGnssAntennaCalControl(C::mip_interface& device); -CmdResult loadGnssAntennaCalControl(C::mip_interface& device); -CmdResult defaultGnssAntennaCalControl(C::mip_interface& device); -///@} -/// -//////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetic_declination_source (0x0D,0x43) Magnetic Declination Source [CPP] -/// Source for magnetic declination angle, and user supplied value for manual selection. -/// -///@{ - -struct MagneticDeclinationSource -{ - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_DECLINATION_SOURCE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - - FunctionSelector function = static_cast(0); - FilterMagDeclinationSource source = static_cast(0); ///< Magnetic field declination angle source - float declination = 0; ///< Declination angle used when 'source' is set to 'MANUAL' (radians) - - struct Response - { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_DECLINATION_SOURCE; - - FilterMagDeclinationSource source = static_cast(0); ///< Magnetic field declination angle source - float declination = 0; ///< Declination angle used when 'source' is set to 'MANUAL' (radians) - - }; -}; -void insert(Serializer& serializer, const MagneticDeclinationSource& self); -void extract(Serializer& serializer, MagneticDeclinationSource& self); - -void insert(Serializer& serializer, const MagneticDeclinationSource::Response& self); -void extract(Serializer& serializer, MagneticDeclinationSource::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); +TypedResult loadGnssAntennaCalControl(C::mip_interface& device); +TypedResult defaultGnssAntennaCalControl(C::mip_interface& device); -CmdResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagDeclinationSource source, float declination); -CmdResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagDeclinationSource* sourceOut, float* declinationOut); -CmdResult saveMagneticDeclinationSource(C::mip_interface& device); -CmdResult loadMagneticDeclinationSource(C::mip_interface& device); -CmdResult defaultMagneticDeclinationSource(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1826,18 +4366,33 @@ CmdResult defaultMagneticDeclinationSource(C::mip_interface& device); struct SetInitialHeading { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SET_INITIAL_HEADING; + float heading = 0; ///< Initial heading in radians [-pi, pi] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float heading = 0; ///< Initial heading in radians [-pi, pi] + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + auto as_tuple() const + { + return std::make_tuple(heading); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(heading)); + } + typedef void Response; }; void insert(Serializer& serializer, const SetInitialHeading& self); void extract(Serializer& serializer, SetInitialHeading& self); -CmdResult setInitialHeading(C::mip_interface& device, float heading); +TypedResult setInitialHeading(C::mip_interface& device, float heading); + ///@} /// diff --git a/src/mip/definitions/commands_gnss.c b/src/mip/definitions/commands_gnss.c index 2de3d6d6d..cb41c03a3 100644 --- a/src/mip/definitions/commands_gnss.c +++ b/src/mip/definitions/commands_gnss.c @@ -367,35 +367,6 @@ mip_cmd_result mip_gnss_default_rtk_dongle_configuration(struct mip_interface* d 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)); } -void insert_mip_gnss_receiver_safe_mode_command(mip_serializer* serializer, const mip_gnss_receiver_safe_mode_command* self) -{ - insert_u8(serializer, self->receiver_id); - - insert_u8(serializer, self->enable); - -} -void extract_mip_gnss_receiver_safe_mode_command(mip_serializer* serializer, mip_gnss_receiver_safe_mode_command* self) -{ - extract_u8(serializer, &self->receiver_id); - - extract_u8(serializer, &self->enable); - -} - -mip_cmd_result mip_gnss_receiver_safe_mode(struct mip_interface* device, uint8_t receiver_id, uint8_t enable) -{ - mip_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_u8(&serializer, receiver_id); - - insert_u8(&serializer, enable); - - assert(mip_serializer_is_ok(&serializer)); - - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RECEIVER_SAFE_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); -} #ifdef __cplusplus } // namespace C diff --git a/src/mip/definitions/commands_gnss.cpp b/src/mip/definitions/commands_gnss.cpp index 28396592e..f980f2e9c 100644 --- a/src/mip/definitions/commands_gnss.cpp +++ b/src/mip/definitions/commands_gnss.cpp @@ -50,7 +50,7 @@ void insert(Serializer& serializer, const ReceiverInfo::Response& self) } void extract(Serializer& serializer, ReceiverInfo::Response& self) { - C::extract_count(&serializer, &self.num_receivers, self.num_receivers); + 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++) extract(serializer, self.receiver_info[i]); @@ -77,12 +77,12 @@ void extract(Serializer& serializer, ReceiverInfo::Info& self) } -CmdResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut) +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 responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LIST_RECEIVERS, NULL, 0, REPLY_LIST_RECEIVERS, buffer, &responseLength); + 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 ) { @@ -166,7 +166,7 @@ void extract(Serializer& serializer, SignalConfiguration::Response& self) } -CmdResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved) +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)); @@ -188,7 +188,7 @@ CmdResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) +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)); @@ -197,7 +197,7 @@ CmdResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOu assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -224,7 +224,7 @@ CmdResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOu } return result; } -CmdResult saveSignalConfiguration(C::mip_interface& device) +TypedResult saveSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -234,7 +234,7 @@ CmdResult saveSignalConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadSignalConfiguration(C::mip_interface& device) +TypedResult loadSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -244,7 +244,7 @@ CmdResult loadSignalConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultSignalConfiguration(C::mip_interface& device) +TypedResult defaultSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -298,7 +298,7 @@ void extract(Serializer& serializer, RtkDongleConfiguration::Response& self) } -CmdResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved) +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)); @@ -314,7 +314,7 @@ CmdResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) +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)); @@ -323,7 +323,7 @@ CmdResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOu assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -341,7 +341,7 @@ CmdResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOu } return result; } -CmdResult saveRtkDongleConfiguration(C::mip_interface& device) +TypedResult saveRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -351,7 +351,7 @@ CmdResult saveRtkDongleConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadRtkDongleConfiguration(C::mip_interface& device) +TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -361,7 +361,7 @@ CmdResult loadRtkDongleConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultRtkDongleConfiguration(C::mip_interface& device) +TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -371,34 +371,6 @@ CmdResult defaultRtkDongleConfiguration(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); } -void insert(Serializer& serializer, const ReceiverSafeMode& self) -{ - insert(serializer, self.receiver_id); - - insert(serializer, self.enable); - -} -void extract(Serializer& serializer, ReceiverSafeMode& self) -{ - extract(serializer, self.receiver_id); - - extract(serializer, self.enable); - -} - -CmdResult receiverSafeMode(C::mip_interface& device, uint8_t receiverId, uint8_t enable) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - insert(serializer, receiverId); - - insert(serializer, enable); - - assert(serializer.isOk()); - - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RECEIVER_SAFE_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); -} } // namespace commands_gnss } // namespace mip diff --git a/src/mip/definitions/commands_gnss.h b/src/mip/definitions/commands_gnss.h index 9a18e418a..2f024f2cc 100644 --- a/src/mip/definitions/commands_gnss.h +++ b/src/mip/definitions/commands_gnss.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -35,7 +36,6 @@ enum MIP_CMD_DESC_GNSS_LIST_RECEIVERS = 0x01, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION = 0x02, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION = 0x10, - MIP_CMD_DESC_GNSS_RECEIVER_SAFE_MODE = 0x60, MIP_REPLY_DESC_GNSS_LIST_RECEIVERS = 0x81, MIP_REPLY_DESC_GNSS_SIGNAL_CONFIGURATION = 0x82, @@ -70,7 +70,7 @@ 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 + 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; @@ -80,7 +80,7 @@ void extract_mip_gnss_receiver_info_command_info(struct mip_serializer* serializ 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; + mip_gnss_receiver_info_command_info receiver_info[5]; }; typedef struct mip_gnss_receiver_info_response mip_gnss_receiver_info_response; @@ -88,6 +88,7 @@ void insert_mip_gnss_receiver_info_response(struct mip_serializer* serializer, c void extract_mip_gnss_receiver_info_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -129,6 +130,7 @@ 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_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device); mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -164,27 +166,7 @@ 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_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); -///@} -/// -//////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_receiver_safe_mode (0x0E,0x60) Receiver Safe Mode [C] -/// Enable/disable safe mode for the provided receiver ID. -/// Note: Receivers in safe mode will not output valid GNSS data. -/// -/// -///@{ - -struct mip_gnss_receiver_safe_mode_command -{ - uint8_t receiver_id; ///< Receiver id: e.g. 1, 2, etc. - uint8_t enable; ///< 0 - Disabled, 1- Enabled - -}; -typedef struct mip_gnss_receiver_safe_mode_command mip_gnss_receiver_safe_mode_command; -void insert_mip_gnss_receiver_safe_mode_command(struct mip_serializer* serializer, const mip_gnss_receiver_safe_mode_command* self); -void extract_mip_gnss_receiver_safe_mode_command(struct mip_serializer* serializer, mip_gnss_receiver_safe_mode_command* self); -mip_cmd_result mip_gnss_receiver_safe_mode(struct mip_interface* device, uint8_t receiver_id, uint8_t enable); ///@} /// diff --git a/src/mip/definitions/commands_gnss.hpp b/src/mip/definitions/commands_gnss.hpp index 643039142..7f3471d7d 100644 --- a/src/mip/definitions/commands_gnss.hpp +++ b/src/mip/definitions/commands_gnss.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -34,7 +35,6 @@ enum CMD_LIST_RECEIVERS = 0x01, CMD_SIGNAL_CONFIGURATION = 0x02, CMD_RTK_DONGLE_CONFIGURATION = 0x10, - CMD_RECEIVER_SAFE_MODE = 0x60, REPLY_LIST_RECEIVERS = 0x81, REPLY_SIGNAL_CONFIGURATION = 0x82, @@ -45,14 +45,14 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -static const uint16_t GNSS_GPS_ENABLE_L1CA = 0x0001; -static const uint16_t GNSS_GPS_ENABLE_L2C = 0x0002; -static const uint16_t GNSS_GLONASS_ENABLE_L1OF = 0x0001; -static const uint16_t GNSS_GLONASS_ENABLE_L2OF = 0x0002; -static const uint16_t GNSS_GALILEO_ENABLE_E1 = 0x0001; -static const uint16_t GNSS_GALILEO_ENABLE_E5B = 0x0002; -static const uint16_t GNSS_BEIDOU_ENABLE_B1 = 0x0001; -static const uint16_t GNSS_BEIDOU_ENABLE_B2 = 0x0002; +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_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_BEIDOU_ENABLE_B1 = 0x0001; +static constexpr const uint16_t GNSS_BEIDOU_ENABLE_B2 = 0x0002; //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -67,27 +67,51 @@ static const uint16_t GNSS_BEIDOU_ENABLE_B2 = 0x0002; struct ReceiverInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::CMD_LIST_RECEIVERS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct Info { 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 + char description[32] = {0}; ///< Ascii description of receiver. Contains the following info (comma-delimited):
Module name/model
Firmware version info }; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::REPLY_LIST_RECEIVERS; + 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 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 = {nullptr}; + Info receiver_info[5]; + + auto as_tuple() + { + return std::make_tuple(std::ref(num_receivers),std::ref(receiver_info)); + } }; }; void insert(Serializer& serializer, const ReceiverInfo& self); @@ -99,7 +123,8 @@ void extract(Serializer& serializer, ReceiverInfo::Info& self); void insert(Serializer& serializer, const ReceiverInfo::Response& self); void extract(Serializer& serializer, ReceiverInfo::Response& self); -CmdResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut); +TypedResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -111,15 +136,6 @@ CmdResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8 struct SignalConfiguration { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::CMD_SIGNAL_CONFIGURATION; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - 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 @@ -127,17 +143,59 @@ struct SignalConfiguration uint8_t beidou_enable = 0; ///< Bitfield 0: Enable B1, 1: Enable B2 uint8_t reserved[4] = {0}; + 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 + { + return std::make_tuple(gps_enable,glonass_enable,galileo_enable,beidou_enable,reserved); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(gps_enable),std::ref(glonass_enable),std::ref(galileo_enable),std::ref(beidou_enable),std::ref(reserved)); + } + + static SignalConfiguration create_sld_all(::mip::FunctionSelector function) + { + SignalConfiguration cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::REPLY_SIGNAL_CONFIGURATION; + 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; 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}; + + auto as_tuple() + { + return std::make_tuple(std::ref(gps_enable),std::ref(glonass_enable),std::ref(galileo_enable),std::ref(beidou_enable),std::ref(reserved)); + } }; }; void insert(Serializer& serializer, const SignalConfiguration& self); @@ -146,11 +204,12 @@ void extract(Serializer& serializer, SignalConfiguration& self); void insert(Serializer& serializer, const SignalConfiguration::Response& self); void extract(Serializer& serializer, SignalConfiguration::Response& self); -CmdResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved); -CmdResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut); -CmdResult saveSignalConfiguration(C::mip_interface& device); -CmdResult loadSignalConfiguration(C::mip_interface& device); -CmdResult defaultSignalConfiguration(C::mip_interface& device); +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); +TypedResult loadSignalConfiguration(C::mip_interface& device); +TypedResult defaultSignalConfiguration(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -162,27 +221,60 @@ CmdResult defaultSignalConfiguration(C::mip_interface& device); struct RtkDongleConfiguration { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::CMD_RTK_DONGLE_CONFIGURATION; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disabled, 1- Enabled uint8_t reserved[3] = {0}; + 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 + { + return std::make_tuple(enable,reserved); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(reserved)); + } + + static RtkDongleConfiguration create_sld_all(::mip::FunctionSelector function) + { + RtkDongleConfiguration cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::REPLY_RTK_DONGLE_CONFIGURATION; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t enable = 0; uint8_t reserved[3] = {0}; + + auto as_tuple() + { + return std::make_tuple(std::ref(enable),std::ref(reserved)); + } }; }; void insert(Serializer& serializer, const RtkDongleConfiguration& self); @@ -191,36 +283,12 @@ void extract(Serializer& serializer, RtkDongleConfiguration& self); void insert(Serializer& serializer, const RtkDongleConfiguration::Response& self); void extract(Serializer& serializer, RtkDongleConfiguration::Response& self); -CmdResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved); -CmdResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut); -CmdResult saveRtkDongleConfiguration(C::mip_interface& device); -CmdResult loadRtkDongleConfiguration(C::mip_interface& device); -CmdResult defaultRtkDongleConfiguration(C::mip_interface& device); -///@} -/// -//////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_receiver_safe_mode (0x0E,0x60) Receiver Safe Mode [CPP] -/// Enable/disable safe mode for the provided receiver ID. -/// Note: Receivers in safe mode will not output valid GNSS data. -/// -/// -///@{ - -struct ReceiverSafeMode -{ - static const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::CMD_RECEIVER_SAFE_MODE; - - static const bool HAS_FUNCTION_SELECTOR = false; - - uint8_t receiver_id = 0; ///< Receiver id: e.g. 1, 2, etc. - uint8_t enable = 0; ///< 0 - Disabled, 1- Enabled - -}; -void insert(Serializer& serializer, const ReceiverSafeMode& self); -void extract(Serializer& serializer, ReceiverSafeMode& 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); +TypedResult loadRtkDongleConfiguration(C::mip_interface& device); +TypedResult defaultRtkDongleConfiguration(C::mip_interface& device); -CmdResult receiverSafeMode(C::mip_interface& device, uint8_t receiverId, uint8_t enable); ///@} /// diff --git a/src/mip/definitions/commands_rtk.c b/src/mip/definitions/commands_rtk.c index 3ff0bd274..d1d1c153d 100644 --- a/src/mip/definitions/commands_rtk.c +++ b/src/mip/definitions/commands_rtk.c @@ -360,7 +360,7 @@ void insert_mip_rtk_service_status_response(mip_serializer* serializer, const mi { insert_mip_rtk_service_status_command_service_flags(serializer, self->flags); - insert_u32(serializer, self->recievedBytes); + insert_u32(serializer, self->receivedBytes); insert_u32(serializer, self->lastBytes); @@ -371,7 +371,7 @@ void extract_mip_rtk_service_status_response(mip_serializer* serializer, mip_rtk { extract_mip_rtk_service_status_command_service_flags(serializer, &self->flags); - extract_u32(serializer, &self->recievedBytes); + extract_u32(serializer, &self->receivedBytes); extract_u32(serializer, &self->lastBytes); @@ -390,7 +390,7 @@ void extract_mip_rtk_service_status_command_service_flags(struct mip_serializer* *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* recieved_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out) +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; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -413,8 +413,8 @@ mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t res assert(flags_out); extract_mip_rtk_service_status_command_service_flags(&deserializer, flags_out); - assert(recieved_bytes_out); - extract_u32(&deserializer, recieved_bytes_out); + assert(received_bytes_out); + extract_u32(&deserializer, received_bytes_out); assert(last_bytes_out); extract_u32(&deserializer, last_bytes_out); diff --git a/src/mip/definitions/commands_rtk.cpp b/src/mip/definitions/commands_rtk.cpp index 65e75b575..2ec4b6dd2 100644 --- a/src/mip/definitions/commands_rtk.cpp +++ b/src/mip/definitions/commands_rtk.cpp @@ -51,12 +51,12 @@ void extract(Serializer& serializer, GetStatusFlags::Response& self) } -CmdResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut) +TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_STATUS_FLAGS, NULL, 0, REPLY_GET_STATUS_FLAGS, buffer, &responseLength); + 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 ) { @@ -94,12 +94,12 @@ void extract(Serializer& serializer, GetImei::Response& self) } -CmdResult getImei(C::mip_interface& device, char* imeiOut) +TypedResult getImei(C::mip_interface& device, char* imeiOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMEI, NULL, 0, REPLY_GET_IMEI, buffer, &responseLength); + 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 ) { @@ -138,12 +138,12 @@ void extract(Serializer& serializer, GetImsi::Response& self) } -CmdResult getImsi(C::mip_interface& device, char* imsiOut) +TypedResult getImsi(C::mip_interface& device, char* imsiOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMSI, NULL, 0, REPLY_GET_IMSI, buffer, &responseLength); + 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 ) { @@ -182,12 +182,12 @@ void extract(Serializer& serializer, GetIccid::Response& self) } -CmdResult getIccid(C::mip_interface& device, char* iccidOut) +TypedResult getIccid(C::mip_interface& device, char* iccidOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_ICCID, NULL, 0, REPLY_GET_ICCID, buffer, &responseLength); + 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 ) { @@ -234,7 +234,7 @@ void extract(Serializer& serializer, ConnectedDeviceType::Response& self) } -CmdResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype) +TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -246,7 +246,7 @@ CmdResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) +TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -255,7 +255,7 @@ CmdResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType: assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -269,7 +269,7 @@ CmdResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType: } return result; } -CmdResult saveConnectedDeviceType(C::mip_interface& device) +TypedResult saveConnectedDeviceType(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -279,7 +279,7 @@ CmdResult saveConnectedDeviceType(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult loadConnectedDeviceType(C::mip_interface& device) +TypedResult loadConnectedDeviceType(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -289,7 +289,7 @@ CmdResult loadConnectedDeviceType(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult defaultConnectedDeviceType(C::mip_interface& device) +TypedResult defaultConnectedDeviceType(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -323,12 +323,12 @@ void extract(Serializer& serializer, GetActCode::Response& self) } -CmdResult getActCode(C::mip_interface& device, char* activationcodeOut) +TypedResult getActCode(C::mip_interface& device, char* activationcodeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_ACT_CODE, NULL, 0, REPLY_GET_ACT_CODE, buffer, &responseLength); + 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 ) { @@ -367,12 +367,12 @@ void extract(Serializer& serializer, GetModemFirmwareVersion::Response& self) } -CmdResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut) +TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_MODEM_FIRMWARE_VERSION, NULL, 0, REPLY_GET_MODEM_FIRMWARE_VERSION, buffer, &responseLength); + 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 ) { @@ -417,12 +417,12 @@ void extract(Serializer& serializer, GetRssi::Response& self) } -CmdResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut) +TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - CmdResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_RSSI, NULL, 0, REPLY_GET_RSSI, buffer, &responseLength); + 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 ) { @@ -461,7 +461,7 @@ void insert(Serializer& serializer, const ServiceStatus::Response& self) { insert(serializer, self.flags); - insert(serializer, self.recievedBytes); + insert(serializer, self.receivedBytes); insert(serializer, self.lastBytes); @@ -472,7 +472,7 @@ void extract(Serializer& serializer, ServiceStatus::Response& self) { extract(serializer, self.flags); - extract(serializer, self.recievedBytes); + extract(serializer, self.receivedBytes); extract(serializer, self.lastBytes); @@ -480,7 +480,7 @@ void extract(Serializer& serializer, ServiceStatus::Response& self) } -CmdResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* recievedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut) +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)); @@ -492,7 +492,7 @@ CmdResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t r assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_SERVICE_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -501,8 +501,8 @@ CmdResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t r assert(flagsOut); extract(deserializer, *flagsOut); - assert(recievedbytesOut); - extract(deserializer, *recievedbytesOut); + assert(receivedbytesOut); + extract(deserializer, *receivedbytesOut); assert(lastbytesOut); extract(deserializer, *lastbytesOut); @@ -526,7 +526,7 @@ void extract(Serializer& serializer, ProdEraseStorage& self) } -CmdResult prodEraseStorage(C::mip_interface& device, MediaSelector media) +TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -564,7 +564,7 @@ void extract(Serializer& serializer, LedControl& self) } -CmdResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period) +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)); @@ -596,7 +596,7 @@ void extract(Serializer& serializer, ModemHardReset& self) (void)self; } -CmdResult modemHardReset(C::mip_interface& device) +TypedResult modemHardReset(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MODEM_HARD_RESET, NULL, 0); } diff --git a/src/mip/definitions/commands_rtk.h b/src/mip/definitions/commands_rtk.h index 34f849d6e..6271716eb 100644 --- a/src/mip/definitions/commands_rtk.h +++ b/src/mip/definitions/commands_rtk.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -98,6 +99,7 @@ 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_RSRP = 0x0C000000; ///< 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; 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; @@ -108,11 +110,12 @@ 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_TOWER_CHANGE_INDICATOR = 0x00F00000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_NMEA_TIMEOUT = 0x01000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_SERVER_TIMEOUT = 0x02000000; ///< -static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_RTCM_TIMEOUT = 0x04000000; ///< +static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_CORRECTIONS_TIMEOUT = 0x04000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_DEVICE_OUT_OF_RANGE = 0x08000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_CORRECTIONS_UNAVAILABLE = 0x10000000; ///< 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; 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); @@ -130,6 +133,7 @@ void insert_mip_rtk_get_status_flags_response(struct mip_serializer* serializer, void extract_mip_rtk_get_status_flags_response(struct mip_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,6 +151,7 @@ void insert_mip_rtk_get_imei_response(struct mip_serializer* serializer, const m void extract_mip_rtk_get_imei_response(struct mip_serializer* serializer, mip_rtk_get_imei_response* self); mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -164,6 +169,7 @@ void insert_mip_rtk_get_imsi_response(struct mip_serializer* serializer, const m void extract_mip_rtk_get_imsi_response(struct mip_serializer* serializer, mip_rtk_get_imsi_response* self); mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -181,6 +187,7 @@ void insert_mip_rtk_get_iccid_response(struct mip_serializer* serializer, const void extract_mip_rtk_get_iccid_response(struct mip_serializer* serializer, mip_rtk_get_iccid_response* self); mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -219,6 +226,7 @@ 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_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -236,6 +244,7 @@ void insert_mip_rtk_get_act_code_response(struct mip_serializer* serializer, con void extract_mip_rtk_get_act_code_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -253,6 +262,7 @@ void insert_mip_rtk_get_modem_firmware_version_response(struct mip_serializer* s void extract_mip_rtk_get_modem_firmware_version_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -273,6 +283,7 @@ void insert_mip_rtk_get_rssi_response(struct mip_serializer* serializer, const m void extract_mip_rtk_get_rssi_response(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -286,6 +297,7 @@ 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_THROTTLE = 0x01; ///< 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; struct mip_rtk_service_status_command { @@ -303,7 +315,7 @@ void extract_mip_rtk_service_status_command_service_flags(struct mip_serializer* struct mip_rtk_service_status_response { mip_rtk_service_status_command_service_flags flags; - uint32_t recievedBytes; + uint32_t receivedBytes; uint32_t lastBytes; uint64_t lastBytesTime; @@ -312,12 +324,13 @@ 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); -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* recieved_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out); +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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_rtk_prod_erase_storage (0x0F,0x20) Prod Erase Storage [C] -/// This command will erase the selected media to a raw and unitialized state. ALL DATA WILL BE LOST. +/// 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. /// ///@{ @@ -332,6 +345,7 @@ void insert_mip_rtk_prod_erase_storage_command(struct mip_serializer* serializer void extract_mip_rtk_prod_erase_storage_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -353,6 +367,7 @@ void insert_mip_rtk_led_control_command(struct mip_serializer* serializer, const void extract_mip_rtk_led_control_command(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -363,6 +378,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); + ///@} /// diff --git a/src/mip/definitions/commands_rtk.hpp b/src/mip/definitions/commands_rtk.hpp index c91b4bbf3..5ee697759 100644 --- a/src/mip/definitions/commands_rtk.hpp +++ b/src/mip/definitions/commands_rtk.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -84,11 +85,6 @@ enum class LedAction : uint8_t struct GetStatusFlags { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_STATUS_FLAGS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct StatusFlagsLegacy : Bitfield { enum _enumType : uint32_t @@ -105,6 +101,7 @@ struct GetStatusFlags RSRP = 0x0C000000, ///< RSRQ = 0x30000000, ///< SINR = 0xC0000000, ///< + ALL = 0xFFFFFFFF, }; uint32_t value = NONE; @@ -112,9 +109,35 @@ struct GetStatusFlags StatusFlagsLegacy(int val) : value((uint32_t)val) {} operator uint32_t() const { return value; } StatusFlagsLegacy& operator=(uint32_t val) { value = val; return *this; } - StatusFlagsLegacy& operator=(int val) { value = val; return *this; } + StatusFlagsLegacy& operator=(int val) { value = uint32_t(val); return *this; } 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 @@ -129,11 +152,12 @@ struct GetStatusFlags TOWER_CHANGE_INDICATOR = 0x00F00000, ///< NMEA_TIMEOUT = 0x01000000, ///< SERVER_TIMEOUT = 0x02000000, ///< - RTCM_TIMEOUT = 0x04000000, ///< + CORRECTIONS_TIMEOUT = 0x04000000, ///< DEVICE_OUT_OF_RANGE = 0x08000000, ///< CORRECTIONS_UNAVAILABLE = 0x10000000, ///< RESERVED = 0x20000000, ///< VERSION = 0xC0000000, ///< + ALL = 0xFFFFFFFF, }; uint32_t value = NONE; @@ -141,19 +165,76 @@ struct GetStatusFlags StatusFlags(int val) : value((uint32_t)val) {} operator uint32_t() const { return value; } StatusFlags& operator=(uint32_t val) { value = val; return *this; } - StatusFlags& operator=(int val) { value = val; return *this; } + StatusFlags& operator=(int val) { value = uint32_t(val); return *this; } 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; } }; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_STATUS_FLAGS; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; StatusFlags flags; ///< Model number dependent. See above structures. + + auto as_tuple() + { + return std::make_tuple(std::ref(flags)); + } }; }; void insert(Serializer& serializer, const GetStatusFlags& self); @@ -162,7 +243,8 @@ void extract(Serializer& serializer, GetStatusFlags& self); void insert(Serializer& serializer, const GetStatusFlags::Response& self); void extract(Serializer& serializer, GetStatusFlags::Response& self); -CmdResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut); +TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -172,19 +254,43 @@ CmdResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* struct GetImei { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_IMEI; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_IMEI; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; char IMEI[32] = {0}; + + auto as_tuple() + { + return std::make_tuple(std::ref(IMEI)); + } }; }; void insert(Serializer& serializer, const GetImei& self); @@ -193,7 +299,8 @@ void extract(Serializer& serializer, GetImei& self); void insert(Serializer& serializer, const GetImei::Response& self); void extract(Serializer& serializer, GetImei::Response& self); -CmdResult getImei(C::mip_interface& device, char* imeiOut); +TypedResult getImei(C::mip_interface& device, char* imeiOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -203,19 +310,43 @@ CmdResult getImei(C::mip_interface& device, char* imeiOut); struct GetImsi { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_IMSI; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_IMSI; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; char IMSI[32] = {0}; + + auto as_tuple() + { + return std::make_tuple(std::ref(IMSI)); + } }; }; void insert(Serializer& serializer, const GetImsi& self); @@ -224,7 +355,8 @@ void extract(Serializer& serializer, GetImsi& self); void insert(Serializer& serializer, const GetImsi::Response& self); void extract(Serializer& serializer, GetImsi::Response& self); -CmdResult getImsi(C::mip_interface& device, char* imsiOut); +TypedResult getImsi(C::mip_interface& device, char* imsiOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -234,19 +366,43 @@ CmdResult getImsi(C::mip_interface& device, char* imsiOut); struct GetIccid { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_ICCID; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_ICCID; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; char ICCID[32] = {0}; + + auto as_tuple() + { + return std::make_tuple(std::ref(ICCID)); + } }; }; void insert(Serializer& serializer, const GetIccid& self); @@ -255,7 +411,8 @@ void extract(Serializer& serializer, GetIccid& self); void insert(Serializer& serializer, const GetIccid::Response& self); void extract(Serializer& serializer, GetIccid::Response& self); -CmdResult getIccid(C::mip_interface& device, char* iccidOut); +TypedResult getIccid(C::mip_interface& device, char* iccidOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -265,15 +422,6 @@ CmdResult getIccid(C::mip_interface& device, char* iccidOut); struct ConnectedDeviceType { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_CONNECTED_DEVICE_TYPE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = true; - static const bool HAS_LOAD_FUNCTION = true; - static const bool HAS_RESET_FUNCTION = true; - enum class Type : uint8_t { GENERIC = 0, ///< @@ -283,13 +431,55 @@ struct ConnectedDeviceType FunctionSelector function = static_cast(0); Type devType = static_cast(0); + 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 + { + return std::make_tuple(devType); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(devType)); + } + + static ConnectedDeviceType create_sld_all(::mip::FunctionSelector function) + { + ConnectedDeviceType cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_CONNECTED_DEVICE_TYPE; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; Type devType = static_cast(0); + + auto as_tuple() + { + return std::make_tuple(std::ref(devType)); + } }; }; void insert(Serializer& serializer, const ConnectedDeviceType& self); @@ -298,11 +488,12 @@ void extract(Serializer& serializer, ConnectedDeviceType& self); void insert(Serializer& serializer, const ConnectedDeviceType::Response& self); void extract(Serializer& serializer, ConnectedDeviceType::Response& self); -CmdResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype); -CmdResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut); -CmdResult saveConnectedDeviceType(C::mip_interface& device); -CmdResult loadConnectedDeviceType(C::mip_interface& device); -CmdResult defaultConnectedDeviceType(C::mip_interface& device); +TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype); +TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut); +TypedResult saveConnectedDeviceType(C::mip_interface& device); +TypedResult loadConnectedDeviceType(C::mip_interface& device); +TypedResult defaultConnectedDeviceType(C::mip_interface& device); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -312,19 +503,43 @@ CmdResult defaultConnectedDeviceType(C::mip_interface& device); struct GetActCode { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_ACT_CODE; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_ACT_CODE; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; char ActivationCode[32] = {0}; + + auto as_tuple() + { + return std::make_tuple(std::ref(ActivationCode)); + } }; }; void insert(Serializer& serializer, const GetActCode& self); @@ -333,7 +548,8 @@ void extract(Serializer& serializer, GetActCode& self); void insert(Serializer& serializer, const GetActCode::Response& self); void extract(Serializer& serializer, GetActCode::Response& self); -CmdResult getActCode(C::mip_interface& device, char* activationcodeOut); +TypedResult getActCode(C::mip_interface& device, char* activationcodeOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -343,19 +559,43 @@ CmdResult getActCode(C::mip_interface& device, char* activationcodeOut); struct GetModemFirmwareVersion { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_MODEM_FIRMWARE_VERSION; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_MODEM_FIRMWARE_VERSION; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; char ModemFirmwareVersion[32] = {0}; + + auto as_tuple() + { + return std::make_tuple(std::ref(ModemFirmwareVersion)); + } }; }; void insert(Serializer& serializer, const GetModemFirmwareVersion& self); @@ -364,7 +604,8 @@ void extract(Serializer& serializer, GetModemFirmwareVersion& self); void insert(Serializer& serializer, const GetModemFirmwareVersion::Response& self); void extract(Serializer& serializer, GetModemFirmwareVersion::Response& self); -CmdResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut); +TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -375,21 +616,45 @@ CmdResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwarev struct GetRssi { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_RSSI; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + + auto as_tuple() + { + return std::make_tuple(); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_RSSI; + 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 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 as_tuple() + { + return std::make_tuple(std::ref(valid),std::ref(rssi),std::ref(signalQuality)); + } }; }; void insert(Serializer& serializer, const GetRssi& self); @@ -398,7 +663,8 @@ void extract(Serializer& serializer, GetRssi& self); void insert(Serializer& serializer, const GetRssi::Response& self); void extract(Serializer& serializer, GetRssi::Response& self); -CmdResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut); +TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -409,11 +675,6 @@ CmdResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, in struct ServiceStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_SERVICE_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ServiceFlags : Bitfield { enum _enumType : uint8_t @@ -422,6 +683,7 @@ struct ServiceStatus THROTTLE = 0x01, ///< CORRECTIONS_UNAVAILABLE = 0x02, ///< RESERVED = 0xFC, ///< + ALL = 0xFF, }; uint8_t value = NONE; @@ -429,24 +691,63 @@ struct ServiceStatus ServiceFlags(int val) : value((uint8_t)val) {} operator uint8_t() const { return value; } ServiceFlags& operator=(uint8_t val) { value = val; return *this; } - ServiceFlags& operator=(int val) { value = val; return *this; } + ServiceFlags& operator=(int val) { value = uint8_t(val); return *this; } 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; } }; uint32_t reserved1 = 0; uint32_t reserved2 = 0; + 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 + { + return std::make_tuple(reserved1,reserved2); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(reserved1),std::ref(reserved2)); + } struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_SERVICE_STATUS; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; ServiceFlags flags; - uint32_t recievedBytes = 0; + uint32_t receivedBytes = 0; uint32_t lastBytes = 0; uint64_t lastBytesTime = 0; + + auto as_tuple() + { + return std::make_tuple(std::ref(flags),std::ref(receivedBytes),std::ref(lastBytes),std::ref(lastBytesTime)); + } }; }; void insert(Serializer& serializer, const ServiceStatus& self); @@ -455,30 +756,46 @@ void extract(Serializer& serializer, ServiceStatus& self); void insert(Serializer& serializer, const ServiceStatus::Response& self); void extract(Serializer& serializer, ServiceStatus::Response& self); -CmdResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* recievedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut); +TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_rtk_prod_erase_storage (0x0F,0x20) Prod Erase Storage [CPP] -/// This command will erase the selected media to a raw and unitialized state. ALL DATA WILL BE LOST. +/// 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. /// ///@{ struct ProdEraseStorage { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_PROD_ERASE_STORAGE; + MediaSelector media = static_cast(0); - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - MediaSelector media = static_cast(0); + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + auto as_tuple() const + { + return std::make_tuple(media); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(media)); + } + typedef void Response; }; void insert(Serializer& serializer, const ProdEraseStorage& self); void extract(Serializer& serializer, ProdEraseStorage& self); -CmdResult prodEraseStorage(C::mip_interface& device, MediaSelector media); +TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -489,21 +806,36 @@ CmdResult prodEraseStorage(C::mip_interface& device, MediaSelector media); struct LedControl { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_CONTROL; - - static const bool HAS_FUNCTION_SELECTOR = false; - uint8_t primaryColor[3] = {0}; uint8_t altColor[3] = {0}; LedAction act = static_cast(0); uint32_t period = 0; + 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 + { + return std::make_tuple(primaryColor,altColor,act,period); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(primaryColor),std::ref(altColor),std::ref(act),std::ref(period)); + } + typedef void Response; }; void insert(Serializer& serializer, const LedControl& self); void extract(Serializer& serializer, LedControl& self); -CmdResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period); +TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -515,17 +847,32 @@ CmdResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, cons struct ModemHardReset { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_MODEM_HARD_RESET; - static const bool HAS_FUNCTION_SELECTOR = false; + 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 + { + return std::make_tuple(); + } + auto as_tuple() + { + return std::make_tuple(); + } + typedef void Response; }; void insert(Serializer& serializer, const ModemHardReset& self); void extract(Serializer& serializer, ModemHardReset& self); -CmdResult modemHardReset(C::mip_interface& device); +TypedResult modemHardReset(C::mip_interface& device); + ///@} /// diff --git a/src/mip/definitions/commands_system.cpp b/src/mip/definitions/commands_system.cpp index 749941ce0..748a9c184 100644 --- a/src/mip/definitions/commands_system.cpp +++ b/src/mip/definitions/commands_system.cpp @@ -61,7 +61,7 @@ void extract(Serializer& serializer, CommMode::Response& self) } -CmdResult writeCommMode(C::mip_interface& device, uint8_t mode) +TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -73,7 +73,7 @@ CmdResult writeCommMode(C::mip_interface& device, uint8_t mode) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); } -CmdResult readCommMode(C::mip_interface& device, uint8_t* modeOut) +TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -82,7 +82,7 @@ CmdResult readCommMode(C::mip_interface& device, uint8_t* modeOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - CmdResult 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)mip_serializer_length(&serializer), REPLY_COM_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -96,7 +96,7 @@ CmdResult readCommMode(C::mip_interface& device, uint8_t* modeOut) } return result; } -CmdResult defaultCommMode(C::mip_interface& device) +TypedResult defaultCommMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); diff --git a/src/mip/definitions/commands_system.h b/src/mip/definitions/commands_system.h index f890553c2..ebdd56585 100644 --- a/src/mip/definitions/commands_system.h +++ b/src/mip/definitions/commands_system.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -91,6 +92,7 @@ void extract_mip_system_comm_mode_response(struct mip_serializer* serializer, mi 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); + ///@} /// diff --git a/src/mip/definitions/commands_system.hpp b/src/mip/definitions/commands_system.hpp index 812075097..90b1e88fa 100644 --- a/src/mip/definitions/commands_system.hpp +++ b/src/mip/definitions/commands_system.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -45,10 +46,10 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -static const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_PASSTHRU = 0x00; -static const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_NORMAL = 0x01; -static const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_IMU = 0x02; -static const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_GPS = 0x03; +static constexpr const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_PASSTHRU = 0x00; +static constexpr const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_NORMAL = 0x01; +static constexpr const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_IMU = 0x02; +static constexpr const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_GPS = 0x03; //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -70,25 +71,58 @@ static const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_GPS = 0x03; struct CommMode { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_system::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_system::CMD_COM_MODE; - - static const bool HAS_WRITE_FUNCTION = true; - static const bool HAS_READ_FUNCTION = true; - static const bool HAS_SAVE_FUNCTION = false; - static const bool HAS_LOAD_FUNCTION = false; - static const bool HAS_RESET_FUNCTION = true; - FunctionSelector function = static_cast(0); uint8_t mode = 0; + 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 + { + return std::make_tuple(mode); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(mode)); + } + + static CommMode create_sld_all(::mip::FunctionSelector function) + { + CommMode cmd; + cmd.function = function; + return cmd; + } + struct Response { - static const uint8_t DESCRIPTOR_SET = ::mip::commands_system::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::commands_system::REPLY_COM_MODE; + 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 uint32_t ECHOED_PARAMS = 0x0000; + static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; uint8_t mode = 0; + + auto as_tuple() + { + return std::make_tuple(std::ref(mode)); + } }; }; void insert(Serializer& serializer, const CommMode& self); @@ -97,9 +131,10 @@ void extract(Serializer& serializer, CommMode& self); void insert(Serializer& serializer, const CommMode::Response& self); void extract(Serializer& serializer, CommMode::Response& self); -CmdResult writeCommMode(C::mip_interface& device, uint8_t mode); -CmdResult readCommMode(C::mip_interface& device, uint8_t* modeOut); -CmdResult defaultCommMode(C::mip_interface& device); +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/mip/definitions/common.c b/src/mip/definitions/common.c new file mode 100644 index 000000000..686d4885a --- /dev/null +++ b/src/mip/definitions/common.c @@ -0,0 +1,39 @@ + +#include "common.h" + +#include "../utils/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); +} + +void extract_mip_descriptor_rate(mip_serializer* serializer, mip_descriptor_rate* self) +{ + extract_u8(serializer, &self->descriptor); + extract_u16(serializer, &self->decimation); +} + +#define IMPLEMENT_MIP_VECTOR_FUNCTIONS(n,type,name) \ +void insert_##name(mip_serializer* serializer, const name self) \ +{ \ + for(unsigned int i=0; i +#include +#include +#include "../utils/serialization.h" + +#ifdef __cplusplus + +#include +#include +#include + +namespace mip { +namespace C { +extern "C" { +#endif // __cplusplus + + +typedef struct mip_descriptor_rate +{ + uint8_t descriptor; + uint16_t decimation; +} mip_descriptor_rate; + +void insert_mip_descriptor_rate(mip_serializer* serializer, const mip_descriptor_rate* self); +void extract_mip_descriptor_rate(mip_serializer* serializer, mip_descriptor_rate* self); + +#define DECLARE_MIP_VECTOR_TYPE(n,type,name) \ +typedef type name[n]; \ +\ +void insert_##name(mip_serializer* serializer, const name self); \ +void extract_##name(mip_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, 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) + +#undef DECLARE_MIP_VECTOR_TYPE + + +#ifdef __cplusplus + +} // extern "C" +} // namespace "C" + + +using DescriptorRate = C::mip_descriptor_rate; + +inline void insert(Serializer& serializer, const DescriptorRate& self) { return C::insert_mip_descriptor_rate(&serializer, &self); } +inline void extract(Serializer& serializer, DescriptorRate& self) { return C::extract_mip_descriptor_rate(&serializer, &self); } + + +////////////////////////////////////////////////////////////////////////////////// +///@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(Serializer& serializer, const Vector& v) { for(size_t i=0; i +void extract(Serializer& serializer, Vector& v) { for(size_t i=0; iframe_id); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->translation[i]); + + for(unsigned int i=0; i < 4; i++) + 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); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->translation[i]); + + for(unsigned int i=0; i < 4; i++) + extract_float(serializer, &self->attitude[i]); + +} +bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_field* field, void* ptr) +{ + assert(ptr); + mip_filter_aiding_frame_config_error_data* self = ptr; + 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); +} + +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); + + for(unsigned int i=0; i < 3; i++) + insert_float(serializer, self->translation_unc[i]); + + for(unsigned int i=0; i < 3; i++) + 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); + + for(unsigned int i=0; i < 3; i++) + extract_float(serializer, &self->translation_unc[i]); + + for(unsigned int i=0; i < 3; i++) + 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) +{ + assert(ptr); + mip_filter_aiding_frame_config_error_uncertainty_data* self = ptr; + 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); +} + #ifdef __cplusplus } // namespace C diff --git a/src/mip/definitions/data_filter.cpp b/src/mip/definitions/data_filter.cpp index fdb85f32b..50e8ae9ba 100644 --- a/src/mip/definitions/data_filter.cpp +++ b/src/mip/definitions/data_filter.cpp @@ -1084,6 +1084,52 @@ void extract(Serializer& serializer, GnssDualAntennaStatus& self) } +void insert(Serializer& serializer, const AidingFrameConfigError& self) +{ + insert(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.translation[i]); + + for(unsigned int i=0; i < 4; i++) + insert(serializer, self.attitude[i]); + +} +void extract(Serializer& serializer, AidingFrameConfigError& self) +{ + extract(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.translation[i]); + + for(unsigned int i=0; i < 4; i++) + extract(serializer, self.attitude[i]); + +} + +void insert(Serializer& serializer, const AidingFrameConfigErrorUncertainty& self) +{ + insert(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.translation_unc[i]); + + for(unsigned int i=0; i < 3; i++) + insert(serializer, self.attitude_unc[i]); + +} +void extract(Serializer& serializer, AidingFrameConfigErrorUncertainty& self) +{ + extract(serializer, self.frame_id); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.translation_unc[i]); + + for(unsigned int i=0; i < 3; i++) + extract(serializer, self.attitude_unc[i]); + +} + } // namespace data_filter } // namespace mip diff --git a/src/mip/definitions/data_filter.h b/src/mip/definitions/data_filter.h index 8441cbe98..316db62c9 100644 --- a/src/mip/definitions/data_filter.h +++ b/src/mip/definitions/data_filter.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -92,6 +93,8 @@ enum MIP_DATA_DESC_FILTER_ODOMETER_SCALE_FACTOR_ERROR = 0x47, MIP_DATA_DESC_FILTER_ODOMETER_SCALE_FACTOR_ERROR_UNCERTAINTY = 0x48, MIP_DATA_DESC_FILTER_GNSS_DUAL_ANTENNA_STATUS = 0x49, + MIP_DATA_DESC_FILTER_FRAME_CONFIG_ERROR = 0x50, + MIP_DATA_DESC_FILTER_FRAME_CONFIG_ERROR_UNCERTAINTY = 0x51, }; @@ -151,17 +154,27 @@ static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_ANTENNA_LEVER_A static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_MOUNTING_TRANSFORM_WARNING = 0x0200; ///< 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; 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); 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_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_AIDING_POS_ECEF = 33; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_POS_LLH = 34; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEIGHT_ABOVE_ELLIPSOID = 35; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_ECEF = 40; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_NED = 41; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_BODY_FRAME = 42; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEADING_TRUE = 49; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_MAGNETIC_FIELD = 50; ///< +static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_PRESSURE = 51; ///< 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); @@ -174,6 +187,7 @@ static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_R static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_SAMPLE_TIME_WARNING = 0x08; ///< 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(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); @@ -196,6 +210,7 @@ static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_BEI_B2 static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_BEI_B3 = 0x2000; ///< If 1, the Kalman filter is using Beidou B3 measurements (not available on the GQ7) 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(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); @@ -224,6 +239,7 @@ void insert_mip_filter_position_llh_data(struct mip_serializer* serializer, cons void extract_mip_filter_position_llh_data(struct mip_serializer* serializer, mip_filter_position_llh_data* self); bool extract_mip_filter_position_llh_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -245,6 +261,7 @@ void insert_mip_filter_velocity_ned_data(struct mip_serializer* serializer, cons void extract_mip_filter_velocity_ned_data(struct mip_serializer* serializer, mip_filter_velocity_ned_data* self); bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -255,7 +272,7 @@ bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field* fie /// EQSTART p^{veh} = q^{-1} p^{ned} q EQEND
/// /// Where:
-/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion desrcribing the rotation.
+/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
/// EQSTART 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.
/// EQSTART 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.
/// @@ -263,7 +280,7 @@ bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field* fie struct mip_filter_attitude_quaternion_data { - float q[4]; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND + mip_quatf q; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -272,6 +289,7 @@ void insert_mip_filter_attitude_quaternion_data(struct mip_serializer* serialize void extract_mip_filter_attitude_quaternion_data(struct mip_serializer* serializer, mip_filter_attitude_quaternion_data* self); bool extract_mip_filter_attitude_quaternion_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -292,7 +310,7 @@ bool extract_mip_filter_attitude_quaternion_data_from_field(const struct mip_fie struct mip_filter_attitude_dcm_data { - float dcm[9]; ///< Matrix elements in row-major order. + mip_matrix3f dcm; ///< Matrix elements in row-major order. uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -301,6 +319,7 @@ void insert_mip_filter_attitude_dcm_data(struct mip_serializer* serializer, cons void extract_mip_filter_attitude_dcm_data(struct mip_serializer* serializer, mip_filter_attitude_dcm_data* self); bool extract_mip_filter_attitude_dcm_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -323,6 +342,7 @@ void insert_mip_filter_euler_angles_data(struct mip_serializer* serializer, cons void extract_mip_filter_euler_angles_data(struct mip_serializer* serializer, mip_filter_euler_angles_data* self); bool extract_mip_filter_euler_angles_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -333,7 +353,7 @@ bool extract_mip_filter_euler_angles_data_from_field(const struct mip_field* fie struct mip_filter_gyro_bias_data { - float bias[3]; ///< (x, y, z) [radians/second] + mip_vector3f bias; ///< (x, y, z) [radians/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -342,6 +362,7 @@ void insert_mip_filter_gyro_bias_data(struct mip_serializer* serializer, const m void extract_mip_filter_gyro_bias_data(struct mip_serializer* serializer, mip_filter_gyro_bias_data* self); bool extract_mip_filter_gyro_bias_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -352,7 +373,7 @@ bool extract_mip_filter_gyro_bias_data_from_field(const struct mip_field* field, struct mip_filter_accel_bias_data { - float bias[3]; ///< (x, y, z) [meters/second^2] + mip_vector3f bias; ///< (x, y, z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -361,6 +382,7 @@ void insert_mip_filter_accel_bias_data(struct mip_serializer* serializer, const void extract_mip_filter_accel_bias_data(struct mip_serializer* serializer, mip_filter_accel_bias_data* self); bool extract_mip_filter_accel_bias_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -382,6 +404,7 @@ void insert_mip_filter_position_llh_uncertainty_data(struct mip_serializer* seri void extract_mip_filter_position_llh_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -403,6 +426,7 @@ void insert_mip_filter_velocity_ned_uncertainty_data(struct mip_serializer* seri void extract_mip_filter_velocity_ned_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -425,6 +449,7 @@ void insert_mip_filter_euler_angles_uncertainty_data(struct mip_serializer* seri void extract_mip_filter_euler_angles_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -435,7 +460,7 @@ bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const struct mi struct mip_filter_gyro_bias_uncertainty_data { - float bias_uncert[3]; ///< (x,y,z) [radians/sec] + mip_vector3f bias_uncert; ///< (x,y,z) [radians/sec] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -444,6 +469,7 @@ void insert_mip_filter_gyro_bias_uncertainty_data(struct mip_serializer* seriali void extract_mip_filter_gyro_bias_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -454,7 +480,7 @@ bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const struct mip_f struct mip_filter_accel_bias_uncertainty_data { - float bias_uncert[3]; ///< (x,y,z) [meters/second^2] + mip_vector3f bias_uncert; ///< (x,y,z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -463,6 +489,7 @@ void insert_mip_filter_accel_bias_uncertainty_data(struct mip_serializer* serial void extract_mip_filter_accel_bias_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -473,7 +500,7 @@ bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const struct mip_ /// Upon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error. /// If synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time. /// -/// Note: this data field may be deprecrated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead. +/// Note: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead. /// ///@{ @@ -489,6 +516,7 @@ void insert_mip_filter_timestamp_data(struct mip_serializer* serializer, const m void extract_mip_filter_timestamp_data(struct mip_serializer* serializer, mip_filter_timestamp_data* self); bool extract_mip_filter_timestamp_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -500,7 +528,7 @@ bool extract_mip_filter_timestamp_data_from_field(const struct mip_field* field, 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_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. }; @@ -509,6 +537,7 @@ void insert_mip_filter_status_data(struct mip_serializer* serializer, const mip_ void extract_mip_filter_status_data(struct mip_serializer* serializer, mip_filter_status_data* self); bool extract_mip_filter_status_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -520,7 +549,7 @@ bool extract_mip_filter_status_data_from_field(const struct mip_field* field, vo struct mip_filter_linear_accel_data { - float accel[3]; ///< (x,y,z) [meters/second^2] + mip_vector3f accel; ///< (x,y,z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -529,6 +558,7 @@ void insert_mip_filter_linear_accel_data(struct mip_serializer* serializer, cons void extract_mip_filter_linear_accel_data(struct mip_serializer* serializer, mip_filter_linear_accel_data* self); bool extract_mip_filter_linear_accel_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -539,7 +569,7 @@ bool extract_mip_filter_linear_accel_data_from_field(const struct mip_field* fie struct mip_filter_gravity_vector_data { - float gravity[3]; ///< (x, y, z) [meters/second^2] + mip_vector3f gravity; ///< (x, y, z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -548,6 +578,7 @@ void insert_mip_filter_gravity_vector_data(struct mip_serializer* serializer, co void extract_mip_filter_gravity_vector_data(struct mip_serializer* serializer, mip_filter_gravity_vector_data* self); bool extract_mip_filter_gravity_vector_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -558,7 +589,7 @@ bool extract_mip_filter_gravity_vector_data_from_field(const struct mip_field* f struct mip_filter_comp_accel_data { - float accel[3]; ///< (x,y,z) [meters/second^2] + mip_vector3f accel; ///< (x,y,z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -567,6 +598,7 @@ void insert_mip_filter_comp_accel_data(struct mip_serializer* serializer, const void extract_mip_filter_comp_accel_data(struct mip_serializer* serializer, mip_filter_comp_accel_data* self); bool extract_mip_filter_comp_accel_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -577,7 +609,7 @@ bool extract_mip_filter_comp_accel_data_from_field(const struct mip_field* field struct mip_filter_comp_angular_rate_data { - float gyro[3]; ///< (x, y, z) [radians/second] + mip_vector3f gyro; ///< (x, y, z) [radians/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -586,6 +618,7 @@ void insert_mip_filter_comp_angular_rate_data(struct mip_serializer* serializer, void extract_mip_filter_comp_angular_rate_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -596,7 +629,7 @@ bool extract_mip_filter_comp_angular_rate_data_from_field(const struct mip_field struct mip_filter_quaternion_attitude_uncertainty_data { - float q[4]; ///< [dimensionless] + mip_quatf q; ///< [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -605,6 +638,7 @@ void insert_mip_filter_quaternion_attitude_uncertainty_data(struct mip_serialize void extract_mip_filter_quaternion_attitude_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -624,6 +658,7 @@ void insert_mip_filter_wgs84_gravity_mag_data(struct mip_serializer* serializer, void extract_mip_filter_wgs84_gravity_mag_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -658,6 +693,7 @@ bool extract_mip_filter_heading_update_state_data_from_field(const struct mip_fi 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -682,6 +718,7 @@ void insert_mip_filter_magnetic_model_data(struct mip_serializer* serializer, co void extract_mip_filter_magnetic_model_data(struct mip_serializer* serializer, mip_filter_magnetic_model_data* self); bool extract_mip_filter_magnetic_model_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -692,7 +729,7 @@ bool extract_mip_filter_magnetic_model_data_from_field(const struct mip_field* f struct mip_filter_accel_scale_factor_data { - float scale_factor[3]; ///< (x,y,z) [dimensionless] + mip_vector3f scale_factor; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -701,6 +738,7 @@ void insert_mip_filter_accel_scale_factor_data(struct mip_serializer* serializer void extract_mip_filter_accel_scale_factor_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -711,7 +749,7 @@ bool extract_mip_filter_accel_scale_factor_data_from_field(const struct mip_fiel struct mip_filter_accel_scale_factor_uncertainty_data { - float scale_factor_uncert[3]; ///< (x,y,z) [dimensionless] + mip_vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -720,6 +758,7 @@ void insert_mip_filter_accel_scale_factor_uncertainty_data(struct mip_serializer void extract_mip_filter_accel_scale_factor_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -730,7 +769,7 @@ bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const str struct mip_filter_gyro_scale_factor_data { - float scale_factor[3]; ///< (x,y,z) [dimensionless] + mip_vector3f scale_factor; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -739,6 +778,7 @@ void insert_mip_filter_gyro_scale_factor_data(struct mip_serializer* serializer, void extract_mip_filter_gyro_scale_factor_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -749,7 +789,7 @@ bool extract_mip_filter_gyro_scale_factor_data_from_field(const struct mip_field struct mip_filter_gyro_scale_factor_uncertainty_data { - float scale_factor_uncert[3]; ///< (x,y,z) [dimensionless] + mip_vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -758,6 +798,7 @@ void insert_mip_filter_gyro_scale_factor_uncertainty_data(struct mip_serializer* void extract_mip_filter_gyro_scale_factor_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -768,7 +809,7 @@ bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const stru struct mip_filter_mag_bias_data { - float bias[3]; ///< (x,y,z) [Gauss] + mip_vector3f bias; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -777,6 +818,7 @@ void insert_mip_filter_mag_bias_data(struct mip_serializer* serializer, const mi void extract_mip_filter_mag_bias_data(struct mip_serializer* serializer, mip_filter_mag_bias_data* self); bool extract_mip_filter_mag_bias_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -787,7 +829,7 @@ bool extract_mip_filter_mag_bias_data_from_field(const struct mip_field* field, struct mip_filter_mag_bias_uncertainty_data { - float bias_uncert[3]; ///< (x,y,z) [Gauss] + mip_vector3f bias_uncert; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -796,6 +838,7 @@ void insert_mip_filter_mag_bias_uncertainty_data(struct mip_serializer* serializ void extract_mip_filter_mag_bias_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -821,6 +864,7 @@ void insert_mip_filter_standard_atmosphere_data(struct mip_serializer* serialize void extract_mip_filter_standard_atmosphere_data(struct mip_serializer* serializer, mip_filter_standard_atmosphere_data* self); bool extract_mip_filter_standard_atmosphere_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -844,6 +888,7 @@ void insert_mip_filter_pressure_altitude_data(struct mip_serializer* serializer, void extract_mip_filter_pressure_altitude_data(struct mip_serializer* serializer, mip_filter_pressure_altitude_data* self); bool extract_mip_filter_pressure_altitude_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -862,6 +907,7 @@ void insert_mip_filter_density_altitude_data(struct mip_serializer* serializer, void extract_mip_filter_density_altitude_data(struct mip_serializer* serializer, mip_filter_density_altitude_data* self); bool extract_mip_filter_density_altitude_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -874,7 +920,7 @@ bool extract_mip_filter_density_altitude_data_from_field(const struct mip_field* struct mip_filter_antenna_offset_correction_data { - float offset[3]; ///< (x,y,z) [meters] + mip_vector3f offset; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -883,6 +929,7 @@ void insert_mip_filter_antenna_offset_correction_data(struct mip_serializer* ser void extract_mip_filter_antenna_offset_correction_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -893,7 +940,7 @@ bool extract_mip_filter_antenna_offset_correction_data_from_field(const struct m struct mip_filter_antenna_offset_correction_uncertainty_data { - float offset_uncert[3]; ///< (x,y,z) [meters] + mip_vector3f offset_uncert; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -902,6 +949,7 @@ void insert_mip_filter_antenna_offset_correction_uncertainty_data(struct mip_ser void extract_mip_filter_antenna_offset_correction_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -915,7 +963,7 @@ bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(co struct mip_filter_multi_antenna_offset_correction_data { uint8_t receiver_id; ///< Receiver ID for the receiver to which the antenna is attached - float offset[3]; ///< (x,y,z) [meters] + mip_vector3f offset; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -924,6 +972,7 @@ void insert_mip_filter_multi_antenna_offset_correction_data(struct mip_serialize void extract_mip_filter_multi_antenna_offset_correction_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -935,7 +984,7 @@ bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const st struct mip_filter_multi_antenna_offset_correction_uncertainty_data { uint8_t receiver_id; ///< Receiver ID for the receiver to which the antenna is attached - float offset_uncert[3]; ///< (x,y,z) [meters] + mip_vector3f offset_uncert; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -944,6 +993,7 @@ void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct m void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -956,7 +1006,7 @@ bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_fi struct mip_filter_magnetometer_offset_data { - float hard_iron[3]; ///< (x,y,z) [Gauss] + mip_vector3f hard_iron; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -965,6 +1015,7 @@ void insert_mip_filter_magnetometer_offset_data(struct mip_serializer* serialize void extract_mip_filter_magnetometer_offset_data(struct mip_serializer* serializer, mip_filter_magnetometer_offset_data* self); bool extract_mip_filter_magnetometer_offset_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -977,7 +1028,7 @@ bool extract_mip_filter_magnetometer_offset_data_from_field(const struct mip_fie struct mip_filter_magnetometer_matrix_data { - float soft_iron[9]; ///< Row-major [dimensionless] + mip_matrix3f soft_iron; ///< Row-major [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -986,6 +1037,7 @@ void insert_mip_filter_magnetometer_matrix_data(struct mip_serializer* serialize void extract_mip_filter_magnetometer_matrix_data(struct mip_serializer* serializer, mip_filter_magnetometer_matrix_data* self); bool extract_mip_filter_magnetometer_matrix_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -996,7 +1048,7 @@ bool extract_mip_filter_magnetometer_matrix_data_from_field(const struct mip_fie struct mip_filter_magnetometer_offset_uncertainty_data { - float hard_iron_uncertainty[3]; ///< (x,y,z) [Gauss] + mip_vector3f hard_iron_uncertainty; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -1005,6 +1057,7 @@ void insert_mip_filter_magnetometer_offset_uncertainty_data(struct mip_serialize void extract_mip_filter_magnetometer_offset_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1015,7 +1068,7 @@ bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const st struct mip_filter_magnetometer_matrix_uncertainty_data { - float soft_iron_uncertainty[9]; ///< Row-major [dimensionless] + mip_matrix3f soft_iron_uncertainty; ///< Row-major [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -1024,6 +1077,7 @@ void insert_mip_filter_magnetometer_matrix_uncertainty_data(struct mip_serialize void extract_mip_filter_magnetometer_matrix_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1033,7 +1087,7 @@ bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const st struct mip_filter_magnetometer_covariance_matrix_data { - float covariance[9]; + mip_matrix3f covariance; uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -1042,6 +1096,7 @@ void insert_mip_filter_magnetometer_covariance_matrix_data(struct mip_serializer void extract_mip_filter_magnetometer_covariance_matrix_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1052,7 +1107,7 @@ bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const str struct mip_filter_magnetometer_residual_vector_data { - float residual[3]; ///< (x,y,z) [Gauss] + mip_vector3f residual; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -1061,6 +1116,7 @@ void insert_mip_filter_magnetometer_residual_vector_data(struct mip_serializer* void extract_mip_filter_magnetometer_residual_vector_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1082,6 +1138,7 @@ void insert_mip_filter_clock_correction_data(struct mip_serializer* serializer, void extract_mip_filter_clock_correction_data(struct mip_serializer* serializer, mip_filter_clock_correction_data* self); bool extract_mip_filter_clock_correction_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1103,6 +1160,7 @@ void insert_mip_filter_clock_correction_uncertainty_data(struct mip_serializer* void extract_mip_filter_clock_correction_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1124,6 +1182,7 @@ void insert_mip_filter_gnss_pos_aid_status_data(struct mip_serializer* serialize void extract_mip_filter_gnss_pos_aid_status_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1144,6 +1203,7 @@ void insert_mip_filter_gnss_att_aid_status_data(struct mip_serializer* serialize void extract_mip_filter_gnss_att_aid_status_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1171,6 +1231,7 @@ bool extract_mip_filter_head_aid_status_data_from_field(const struct mip_field* 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1181,7 +1242,7 @@ void extract_mip_filter_head_aid_status_data_heading_aid_type(struct mip_seriali struct mip_filter_rel_pos_ned_data { - double relative_position[3]; ///< [meters, NED] + mip_vector3d relative_position; ///< [meters, NED] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -1190,6 +1251,7 @@ void insert_mip_filter_rel_pos_ned_data(struct mip_serializer* serializer, const void extract_mip_filter_rel_pos_ned_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1200,7 +1262,7 @@ bool extract_mip_filter_rel_pos_ned_data_from_field(const struct mip_field* fiel struct mip_filter_ecef_pos_data { - double position_ecef[3]; ///< [meters, ECEF] + mip_vector3d position_ecef; ///< [meters, ECEF] uint16_t valid_flags; ///< 0 - invalid, 1 valid }; @@ -1209,6 +1271,7 @@ void insert_mip_filter_ecef_pos_data(struct mip_serializer* serializer, const mi void extract_mip_filter_ecef_pos_data(struct mip_serializer* serializer, mip_filter_ecef_pos_data* self); bool extract_mip_filter_ecef_pos_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1219,7 +1282,7 @@ bool extract_mip_filter_ecef_pos_data_from_field(const struct mip_field* field, struct mip_filter_ecef_vel_data { - float velocity_ecef[3]; ///< [meters/second, ECEF] + mip_vector3f velocity_ecef; ///< [meters/second, ECEF] uint16_t valid_flags; ///< 0 - invalid, 1 valid }; @@ -1228,6 +1291,7 @@ void insert_mip_filter_ecef_vel_data(struct mip_serializer* serializer, const mi void extract_mip_filter_ecef_vel_data(struct mip_serializer* serializer, mip_filter_ecef_vel_data* self); bool extract_mip_filter_ecef_vel_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1238,7 +1302,7 @@ bool extract_mip_filter_ecef_vel_data_from_field(const struct mip_field* field, struct mip_filter_ecef_pos_uncertainty_data { - float pos_uncertainty[3]; ///< [meters] + mip_vector3f pos_uncertainty; ///< [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -1247,6 +1311,7 @@ void insert_mip_filter_ecef_pos_uncertainty_data(struct mip_serializer* serializ void extract_mip_filter_ecef_pos_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1257,7 +1322,7 @@ bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const struct mip_fi struct mip_filter_ecef_vel_uncertainty_data { - float vel_uncertainty[3]; ///< [meters/second] + mip_vector3f vel_uncertainty; ///< [meters/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid }; @@ -1266,6 +1331,7 @@ void insert_mip_filter_ecef_vel_uncertainty_data(struct mip_serializer* serializ void extract_mip_filter_ecef_vel_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1278,7 +1344,7 @@ struct mip_filter_aiding_measurement_summary_data { float time_of_week; ///< [seconds] uint8_t source; - mip_filter_aiding_measurement_type type; ///< (see product manual for supported types) + 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; }; @@ -1287,6 +1353,7 @@ void insert_mip_filter_aiding_measurement_summary_data(struct mip_serializer* se void extract_mip_filter_aiding_measurement_summary_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1306,6 +1373,7 @@ void insert_mip_filter_odometer_scale_factor_error_data(struct mip_serializer* s void extract_mip_filter_odometer_scale_factor_error_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1325,6 +1393,7 @@ void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(struct mip_s void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1343,6 +1412,7 @@ 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_1_DATA_VALID = 0x0001; ///< 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; struct mip_filter_gnss_dual_antenna_status_data { @@ -1365,6 +1435,53 @@ void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct mip_serial 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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_aiding_frame_config_error (0x82,0x50) Aiding Frame Config Error [C] +/// 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 ). +/// +///@{ + +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(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); +bool extract_mip_filter_aiding_frame_config_error_data_from_field(const struct mip_field* field, void* ptr); + + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_filter_aiding_frame_config_error_uncertainty (0x82,0x51) Aiding Frame Config Error Uncertainty [C] +/// 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 ). +/// +///@{ + +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(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); +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_filter.hpp b/src/mip/definitions/data_filter.hpp index f8962e5f2..96ab927e2 100644 --- a/src/mip/definitions/data_filter.hpp +++ b/src/mip/definitions/data_filter.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -91,6 +92,8 @@ enum DATA_ODOMETER_SCALE_FACTOR_ERROR = 0x47, DATA_ODOMETER_SCALE_FACTOR_ERROR_UNCERTAINTY = 0x48, DATA_GNSS_DUAL_ANTENNA_STATUS = 0x49, + DATA_FRAME_CONFIG_ERROR = 0x50, + DATA_FRAME_CONFIG_ERROR_UNCERTAINTY = 0x51, }; @@ -151,6 +154,7 @@ struct FilterStatusFlags : Bitfield GQ7_MOUNTING_TRANSFORM_WARNING = 0x0200, ///< GQ7_TIME_SYNC_WARNING = 0x0400, ///< No time synchronization pulse detected GQ7_SOLUTION_ERROR = 0xF000, ///< Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid. + ALL = 0xFFFF, }; uint16_t value = NONE; @@ -158,19 +162,88 @@ struct FilterStatusFlags : Bitfield FilterStatusFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } FilterStatusFlags& operator=(uint16_t val) { value = val; return *this; } - FilterStatusFlags& operator=(int val) { value = val; return *this; } + FilterStatusFlags& operator=(int val) { value = uint16_t(val); return *this; } 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, ///< + 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 @@ -184,6 +257,7 @@ struct FilterMeasurementIndicator : Bitfield SAMPLE_TIME_WARNING = 0x08, ///< CONFIGURATION_ERROR = 0x10, ///< MAX_NUM_MEAS_EXCEEDED = 0x20, ///< + ALL = 0x3F, }; uint8_t value = NONE; @@ -191,9 +265,25 @@ struct FilterMeasurementIndicator : Bitfield FilterMeasurementIndicator(int val) : value((uint8_t)val) {} operator uint8_t() const { return value; } FilterMeasurementIndicator& operator=(uint8_t val) { value = val; return *this; } - FilterMeasurementIndicator& operator=(int val) { value = val; return *this; } + FilterMeasurementIndicator& operator=(int val) { value = uint8_t(val); return *this; } 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 @@ -217,6 +307,7 @@ struct GnssAidStatusFlags : Bitfield BEI_B3 = 0x2000, ///< If 1, the Kalman filter is using Beidou B3 measurements (not available on the GQ7) NO_FIX = 0x4000, ///< If 1, this GNSS module is reporting no position fix CONFIG_ERROR = 0x8000, ///< If 1, there is likely an issue with the antenna offset for this GNSS module + ALL = 0xFFFF, }; uint16_t value = NONE; @@ -224,9 +315,45 @@ struct GnssAidStatusFlags : Bitfield GnssAidStatusFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } GnssAidStatusFlags& operator=(uint16_t val) { value = val; return *this; } - GnssAidStatusFlags& operator=(int val) { value = val; return *this; } + GnssAidStatusFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; @@ -242,20 +369,32 @@ struct GnssAidStatusFlags : Bitfield struct PositionLlh { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_POS_LLH; - - static const bool HAS_FUNCTION_SELECTOR = false; - double latitude = 0; ///< [degrees] double longitude = 0; ///< [degrees] double ellipsoid_height = 0; ///< [meters] uint16_t valid_flags = 0; ///< 0 - Invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(latitude,longitude,ellipsoid_height,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -266,20 +405,32 @@ void extract(Serializer& serializer, PositionLlh& self); struct VelocityNed { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_VEL_NED; - - static const bool HAS_FUNCTION_SELECTOR = false; - float north = 0; ///< [meters/second] float east = 0; ///< [meters/second] float down = 0; ///< [meters/second] uint16_t valid_flags = 0; ///< 0 - Invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(north,east,down,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -290,7 +441,7 @@ void extract(Serializer& serializer, VelocityNed& self); /// EQSTART p^{veh} = q^{-1} p^{ned} q EQEND
/// /// Where:
-/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion desrcribing the rotation.
+/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
/// EQSTART 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.
/// EQSTART 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.
/// @@ -298,18 +449,30 @@ void extract(Serializer& serializer, VelocityNed& self); struct AttitudeQuaternion { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_QUATERNION; + Quatf q; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float q[4] = {0}; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(q[0],q[1],q[2],q[3],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -330,18 +493,30 @@ void extract(Serializer& serializer, AttitudeQuaternion& self); struct AttitudeDcm { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_MATRIX; + Matrix3f dcm; ///< Matrix elements in row-major order. + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float dcm[9] = {0}; ///< Matrix elements in row-major order. - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -353,20 +528,32 @@ void extract(Serializer& serializer, AttitudeDcm& self); struct EulerAngles { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_EULER_ANGLES; - - static const bool HAS_FUNCTION_SELECTOR = false; - float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(roll,pitch,yaw,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -377,18 +564,30 @@ void extract(Serializer& serializer, EulerAngles& self); struct GyroBias { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_BIAS; + Vector3f bias; ///< (x, y, z) [radians/second] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float bias[3] = {0}; ///< (x, y, z) [radians/second] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(bias[0],bias[1],bias[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -399,18 +598,30 @@ void extract(Serializer& serializer, GyroBias& self); struct AccelBias { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_BIAS; + Vector3f bias; ///< (x, y, z) [meters/second^2] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float bias[3] = {0}; ///< (x, y, z) [meters/second^2] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(bias[0],bias[1],bias[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -421,20 +632,32 @@ void extract(Serializer& serializer, AccelBias& self); struct PositionLlhUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_POS_UNCERTAINTY; - - static const bool HAS_FUNCTION_SELECTOR = false; - float north = 0; ///< [meters] float east = 0; ///< [meters] float down = 0; ///< [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(north,east,down,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -445,20 +668,32 @@ void extract(Serializer& serializer, PositionLlhUncertainty& self); struct VelocityNedUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_VEL_UNCERTAINTY; - - static const bool HAS_FUNCTION_SELECTOR = false; - float north = 0; ///< [meters/second] float east = 0; ///< [meters/second] float down = 0; ///< [meters/second] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(north,east,down,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -470,20 +705,32 @@ void extract(Serializer& serializer, VelocityNedUncertainty& self); struct EulerAnglesUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_UNCERTAINTY_EULER; - - static const bool HAS_FUNCTION_SELECTOR = false; - float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(roll,pitch,yaw,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -494,18 +741,30 @@ void extract(Serializer& serializer, EulerAnglesUncertainty& self); struct GyroBiasUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_BIAS_UNCERTAINTY; + Vector3f bias_uncert; ///< (x,y,z) [radians/sec] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float bias_uncert[3] = {0}; ///< (x,y,z) [radians/sec] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(bias_uncert[0],bias_uncert[1],bias_uncert[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -516,18 +775,30 @@ void extract(Serializer& serializer, GyroBiasUncertainty& self); struct AccelBiasUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_BIAS_UNCERTAINTY; + Vector3f bias_uncert; ///< (x,y,z) [meters/second^2] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float bias_uncert[3] = {0}; ///< (x,y,z) [meters/second^2] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(bias_uncert[0],bias_uncert[1],bias_uncert[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -538,25 +809,37 @@ void extract(Serializer& serializer, AccelBiasUncertainty& self); /// Upon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error. /// If synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time. /// -/// Note: this data field may be deprecrated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead. +/// Note: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead. /// ///@{ struct Timestamp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_FILTER_TIMESTAMP; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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 + 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"; + + + auto as_tuple() const + { + return std::make_tuple(tow,week_number,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -567,19 +850,31 @@ void extract(Serializer& serializer, Timestamp& self); struct Status { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_FILTER_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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. + 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. + 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"; + + + auto as_tuple() const + { + return std::make_tuple(filter_state,dynamics_mode,status_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -591,18 +886,30 @@ void extract(Serializer& serializer, Status& self); struct LinearAccel { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_LINEAR_ACCELERATION; + Vector3f accel; ///< (x,y,z) [meters/second^2] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float accel[3] = {0}; ///< (x,y,z) [meters/second^2] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(accel[0],accel[1],accel[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -613,18 +920,30 @@ void extract(Serializer& serializer, LinearAccel& self); struct GravityVector { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GRAVITY_VECTOR; + Vector3f gravity; ///< (x, y, z) [meters/second^2] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float gravity[3] = {0}; ///< (x, y, z) [meters/second^2] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(gravity[0],gravity[1],gravity[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -635,18 +954,30 @@ void extract(Serializer& serializer, GravityVector& self); struct CompAccel { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_COMPENSATED_ACCELERATION; + Vector3f accel; ///< (x,y,z) [meters/second^2] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float accel[3] = {0}; ///< (x,y,z) [meters/second^2] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(accel[0],accel[1],accel[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -657,18 +988,30 @@ void extract(Serializer& serializer, CompAccel& self); struct CompAngularRate { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_COMPENSATED_ANGULAR_RATE; + Vector3f gyro; ///< (x, y, z) [radians/second] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float gyro[3] = {0}; ///< (x, y, z) [radians/second] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(gyro[0],gyro[1],gyro[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -679,18 +1022,30 @@ void extract(Serializer& serializer, CompAngularRate& self); struct QuaternionAttitudeUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_UNCERTAINTY_QUATERNION; + Quatf q; ///< [dimensionless] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float q[4] = {0}; ///< [dimensionless] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(q[0],q[1],q[2],q[3],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -701,18 +1056,30 @@ void extract(Serializer& serializer, QuaternionAttitudeUncertainty& self); struct Wgs84GravityMag { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_WGS84_GRAVITY; - - static const bool HAS_FUNCTION_SELECTOR = false; - float magnitude = 0; ///< [meters/second^2] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(magnitude,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(magnitude),std::ref(valid_flags)); + } }; void insert(Serializer& serializer, const Wgs84GravityMag& self); void extract(Serializer& serializer, Wgs84GravityMag& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -726,11 +1093,6 @@ void extract(Serializer& serializer, Wgs84GravityMag& self); struct HeadingUpdateState { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_HEADING_UPDATE_STATE; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class HeadingSource : uint16_t { NONE = 0, ///< @@ -745,10 +1107,27 @@ struct HeadingUpdateState HeadingSource source = static_cast(0); uint16_t valid_flags = 0; ///< 1 if a valid heading update was received in 2 seconds, 0 otherwise. + 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"; + + + auto as_tuple() const + { + return std::make_tuple(heading,heading_1sigma,source,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -760,11 +1139,6 @@ void extract(Serializer& serializer, HeadingUpdateState& self); struct MagneticModel { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAGNETIC_MODEL; - - static const bool HAS_FUNCTION_SELECTOR = false; - float intensity_north = 0; ///< [Gauss] float intensity_east = 0; ///< [Gauss] float intensity_down = 0; ///< [Gauss] @@ -772,10 +1146,27 @@ struct MagneticModel float declination = 0; ///< [radians] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(intensity_north,intensity_east,intensity_down,inclination,declination,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -786,18 +1177,30 @@ void extract(Serializer& serializer, MagneticModel& self); struct AccelScaleFactor { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_SCALE_FACTOR; + Vector3f scale_factor; ///< (x,y,z) [dimensionless] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scale_factor[3] = {0}; ///< (x,y,z) [dimensionless] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(scale_factor[0],scale_factor[1],scale_factor[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -808,18 +1211,30 @@ void extract(Serializer& serializer, AccelScaleFactor& self); struct AccelScaleFactorUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_SCALE_FACTOR_UNCERTAINTY; + Vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scale_factor_uncert[3] = {0}; ///< (x,y,z) [dimensionless] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(scale_factor_uncert[0],scale_factor_uncert[1],scale_factor_uncert[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -830,18 +1245,30 @@ void extract(Serializer& serializer, AccelScaleFactorUncertainty& self); struct GyroScaleFactor { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_SCALE_FACTOR; + Vector3f scale_factor; ///< (x,y,z) [dimensionless] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scale_factor[3] = {0}; ///< (x,y,z) [dimensionless] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(scale_factor[0],scale_factor[1],scale_factor[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -852,18 +1279,30 @@ void extract(Serializer& serializer, GyroScaleFactor& self); struct GyroScaleFactorUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_SCALE_FACTOR_UNCERTAINTY; + Vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scale_factor_uncert[3] = {0}; ///< (x,y,z) [dimensionless] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(scale_factor_uncert[0],scale_factor_uncert[1],scale_factor_uncert[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -874,18 +1313,30 @@ void extract(Serializer& serializer, GyroScaleFactorUncertainty& self); struct MagBias { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_BIAS; + Vector3f bias; ///< (x,y,z) [Gauss] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float bias[3] = {0}; ///< (x,y,z) [Gauss] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(bias[0],bias[1],bias[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -896,18 +1347,30 @@ void extract(Serializer& serializer, MagBias& self); struct MagBiasUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_BIAS_UNCERTAINTY; + Vector3f bias_uncert; ///< (x,y,z) [Gauss] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float bias_uncert[3] = {0}; ///< (x,y,z) [Gauss] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(bias_uncert[0],bias_uncert[1],bias_uncert[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -920,11 +1383,6 @@ void extract(Serializer& serializer, MagBiasUncertainty& self); struct StandardAtmosphere { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_STANDARD_ATMOSPHERE_DATA; - - static const bool HAS_FUNCTION_SELECTOR = false; - float geometric_altitude = 0; ///< Input into calculation [meters] float geopotential_altitude = 0; ///< [meters] float standard_temperature = 0; ///< [degC] @@ -932,10 +1390,27 @@ struct StandardAtmosphere float standard_density = 0; ///< [kilogram/meter^3] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(geometric_altitude,geopotential_altitude,standard_temperature,standard_pressure,standard_density,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -950,18 +1425,30 @@ void extract(Serializer& serializer, StandardAtmosphere& self); struct PressureAltitude { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_PRESSURE_ALTITUDE_DATA; - - static const bool HAS_FUNCTION_SELECTOR = false; - float pressure_altitude = 0; ///< [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(pressure_altitude,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -971,18 +1458,30 @@ void extract(Serializer& serializer, PressureAltitude& self); struct DensityAltitude { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_DENSITY_ALTITUDE_DATA; - - static const bool HAS_FUNCTION_SELECTOR = false; - float density_altitude = 0; ///< m uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(density_altitude,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -995,18 +1494,30 @@ void extract(Serializer& serializer, DensityAltitude& self); struct AntennaOffsetCorrection { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ANTENNA_OFFSET_CORRECTION; + Vector3f offset; ///< (x,y,z) [meters] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float offset[3] = {0}; ///< (x,y,z) [meters] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(offset[0],offset[1],offset[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1017,18 +1528,30 @@ void extract(Serializer& serializer, AntennaOffsetCorrection& self); struct AntennaOffsetCorrectionUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ANTENNA_OFFSET_CORRECTION_UNCERTAINTY; + Vector3f offset_uncert; ///< (x,y,z) [meters] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float offset_uncert[3] = {0}; ///< (x,y,z) [meters] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(offset_uncert[0],offset_uncert[1],offset_uncert[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1041,19 +1564,31 @@ void extract(Serializer& serializer, AntennaOffsetCorrectionUncertainty& self); struct MultiAntennaOffsetCorrection { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MULTI_ANTENNA_OFFSET_CORRECTION; - - static const bool HAS_FUNCTION_SELECTOR = false; - uint8_t receiver_id = 0; ///< Receiver ID for the receiver to which the antenna is attached - float offset[3] = {0}; ///< (x,y,z) [meters] + Vector3f offset; ///< (x,y,z) [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(receiver_id,offset[0],offset[1],offset[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1064,19 +1599,31 @@ void extract(Serializer& serializer, MultiAntennaOffsetCorrection& self); struct MultiAntennaOffsetCorrectionUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MULTI_ANTENNA_OFFSET_CORRECTION_UNCERTAINTY; - - static const bool HAS_FUNCTION_SELECTOR = false; - uint8_t receiver_id = 0; ///< Receiver ID for the receiver to which the antenna is attached - float offset_uncert[3] = {0}; ///< (x,y,z) [meters] + Vector3f offset_uncert; ///< (x,y,z) [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(receiver_id,offset_uncert[0],offset_uncert[1],offset_uncert[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1089,18 +1636,30 @@ void extract(Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& se struct MagnetometerOffset { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_OFFSET; + Vector3f hard_iron; ///< (x,y,z) [Gauss] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float hard_iron[3] = {0}; ///< (x,y,z) [Gauss] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(hard_iron[0],hard_iron[1],hard_iron[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1113,18 +1672,30 @@ void extract(Serializer& serializer, MagnetometerOffset& self); struct MagnetometerMatrix { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_MATRIX; + Matrix3f soft_iron; ///< Row-major [dimensionless] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float soft_iron[9] = {0}; ///< Row-major [dimensionless] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1135,18 +1706,30 @@ void extract(Serializer& serializer, MagnetometerMatrix& self); struct MagnetometerOffsetUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_OFFSET_UNCERTAINTY; + Vector3f hard_iron_uncertainty; ///< (x,y,z) [Gauss] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float hard_iron_uncertainty[3] = {0}; ///< (x,y,z) [Gauss] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(hard_iron_uncertainty[0],hard_iron_uncertainty[1],hard_iron_uncertainty[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1157,18 +1740,30 @@ void extract(Serializer& serializer, MagnetometerOffsetUncertainty& self); struct MagnetometerMatrixUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_MATRIX_UNCERTAINTY; + Matrix3f soft_iron_uncertainty; ///< Row-major [dimensionless] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float soft_iron_uncertainty[9] = {0}; ///< Row-major [dimensionless] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1178,18 +1773,30 @@ void extract(Serializer& serializer, MagnetometerMatrixUncertainty& self); struct MagnetometerCovarianceMatrix { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COVARIANCE; + Matrix3f covariance; + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float covariance[9] = {0}; - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1200,18 +1807,30 @@ void extract(Serializer& serializer, MagnetometerCovarianceMatrix& self); struct MagnetometerResidualVector { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_RESIDUAL; + Vector3f residual; ///< (x,y,z) [Gauss] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float residual[3] = {0}; ///< (x,y,z) [Gauss] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(residual[0],residual[1],residual[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1222,20 +1841,32 @@ void extract(Serializer& serializer, MagnetometerResidualVector& self); struct ClockCorrection { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_CLOCK_CORRECTION; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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 + 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"; + + + auto as_tuple() const + { + return std::make_tuple(receiver_id,bias,bias_drift,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1246,20 +1877,32 @@ void extract(Serializer& serializer, ClockCorrection& self); struct ClockCorrectionUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_CLOCK_CORRECTION_UNCERTAINTY; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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 + 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"; + + + auto as_tuple() const + { + return std::make_tuple(receiver_id,bias_uncertainty,bias_drift_uncertainty,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1270,20 +1913,32 @@ void extract(Serializer& serializer, ClockCorrectionUncertainty& self); struct GnssPosAidStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GNSS_POS_AID_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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}; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(receiver_id,time_of_week,status,reserved); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1294,19 +1949,31 @@ void extract(Serializer& serializer, GnssPosAidStatus& self); struct GnssAttAidStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GNSS_ATT_AID_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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}; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_of_week,status,reserved); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1317,11 +1984,6 @@ void extract(Serializer& serializer, GnssAttAidStatus& self); struct HeadAidStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_HEAD_AID_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class HeadingAidType : uint8_t { DUAL_ANTENNA = 1, ///< @@ -1332,10 +1994,27 @@ struct HeadAidStatus HeadingAidType type = static_cast(0); ///< 1 - Dual antenna, 2 - External heading message (user supplied) float reserved[2] = {0}; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_of_week,type,reserved); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1346,18 +2025,30 @@ void extract(Serializer& serializer, HeadAidStatus& self); struct RelPosNed { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_REL_POS_NED; + Vector3d relative_position; ///< [meters, NED] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - double relative_position[3] = {0}; ///< [meters, NED] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(relative_position[0],relative_position[1],relative_position[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1368,18 +2059,30 @@ void extract(Serializer& serializer, RelPosNed& self); struct EcefPos { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_POS; + Vector3d position_ecef; ///< [meters, ECEF] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - double position_ecef[3] = {0}; ///< [meters, ECEF] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 valid + auto as_tuple() const + { + return std::make_tuple(position_ecef[0],position_ecef[1],position_ecef[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1390,18 +2093,30 @@ void extract(Serializer& serializer, EcefPos& self); struct EcefVel { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_VEL; + Vector3f velocity_ecef; ///< [meters/second, ECEF] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float velocity_ecef[3] = {0}; ///< [meters/second, ECEF] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 valid + auto as_tuple() const + { + return std::make_tuple(velocity_ecef[0],velocity_ecef[1],velocity_ecef[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1412,18 +2127,30 @@ void extract(Serializer& serializer, EcefVel& self); struct EcefPosUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_POS_UNCERTAINTY; + Vector3f pos_uncertainty; ///< [meters] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float pos_uncertainty[3] = {0}; ///< [meters] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(pos_uncertainty[0],pos_uncertainty[1],pos_uncertainty[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1434,18 +2161,30 @@ void extract(Serializer& serializer, EcefPosUncertainty& self); struct EcefVelUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_VEL_UNCERTAINTY; + Vector3f vel_uncertainty; ///< [meters/second] + uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float vel_uncertainty[3] = {0}; ///< [meters/second] - uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + auto as_tuple() const + { + return std::make_tuple(vel_uncertainty[0],vel_uncertainty[1],vel_uncertainty[2],valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1456,20 +2195,32 @@ void extract(Serializer& serializer, EcefVelUncertainty& self); struct AidingMeasurementSummary { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_AID_MEAS_SUMMARY; - - static const bool HAS_FUNCTION_SELECTOR = false; - float time_of_week = 0; ///< [seconds] uint8_t source = 0; - FilterAidingMeasurementType type = static_cast(0); ///< (see product manual for supported types) + 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; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_of_week,source,type,indicator); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1480,18 +2231,30 @@ void extract(Serializer& serializer, AidingMeasurementSummary& self); struct OdometerScaleFactorError { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ODOMETER_SCALE_FACTOR_ERROR; - - static const bool HAS_FUNCTION_SELECTOR = false; - float scale_factor_error = 0; ///< [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(scale_factor_error,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1502,18 +2265,30 @@ void extract(Serializer& serializer, OdometerScaleFactorError& self); struct OdometerScaleFactorErrorUncertainty { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ODOMETER_SCALE_FACTOR_ERROR_UNCERTAINTY; - - static const bool HAS_FUNCTION_SELECTOR = false; - float scale_factor_error_uncertainty = 0; ///< [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(scale_factor_error_uncertainty,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1524,11 +2299,6 @@ void extract(Serializer& serializer, OdometerScaleFactorErrorUncertainty& self); struct GnssDualAntennaStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GNSS_DUAL_ANTENNA_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class FixType : uint8_t { FIX_NONE = 0, ///< @@ -1544,6 +2314,7 @@ struct GnssDualAntennaStatus RCV_1_DATA_VALID = 0x0001, ///< RCV_2_DATA_VALID = 0x0002, ///< ANTENNA_OFFSETS_VALID = 0x0004, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -1551,9 +2322,19 @@ struct GnssDualAntennaStatus DualAntennaStatusFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } DualAntennaStatusFlags& operator=(uint16_t val) { value = val; return *this; } - DualAntennaStatusFlags& operator=(int val) { value = val; return *this; } + DualAntennaStatusFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; float time_of_week = 0; ///< Last dual-antenna GNSS aiding measurement time of week [seconds] @@ -1563,10 +2344,101 @@ struct GnssDualAntennaStatus DualAntennaStatusFlags status_flags; uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_of_week,heading,heading_unc,fix_type,status_flags,valid_flags); + } + + auto as_tuple() + { + 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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_aiding_frame_config_error (0x82,0x50) Aiding Frame Config Error [CPP] +/// 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 ). +/// +///@{ + +struct AidingFrameConfigError +{ + 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 + + 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"; + + + auto as_tuple() const + { + return std::make_tuple(frame_id,translation[0],translation[1],translation[2],attitude[0],attitude[1],attitude[2],attitude[3]); + } + + auto as_tuple() + { + 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); + + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_filter_aiding_frame_config_error_uncertainty (0x82,0x51) Aiding Frame Config Error Uncertainty [CPP] +/// 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 ). +/// +///@{ + +struct AidingFrameConfigErrorUncertainty +{ + 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). + + 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"; + + + auto as_tuple() 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() + { + 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); + + ///@} /// diff --git a/src/mip/definitions/data_gnss.c b/src/mip/definitions/data_gnss.c index 4a2b28c87..2213a4bd9 100644 --- a/src/mip/definitions/data_gnss.c +++ b/src/mip/definitions/data_gnss.c @@ -1544,6 +1544,169 @@ void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct mip_serializer* seri *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); + + 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); + + 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) +{ + assert(ptr); + mip_gnss_galileo_ephemeris_data* self = ptr; + 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); +} + +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)); +} +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); + *self = tmp; +} + void insert_mip_gnss_glo_ephemeris_data(mip_serializer* serializer, const mip_gnss_glo_ephemeris_data* self) { insert_u8(serializer, self->index); diff --git a/src/mip/definitions/data_gnss.cpp b/src/mip/definitions/data_gnss.cpp index e632168ab..2511644c5 100644 --- a/src/mip/definitions/data_gnss.cpp +++ b/src/mip/definitions/data_gnss.cpp @@ -910,6 +910,149 @@ void extract(Serializer& serializer, GpsEphemeris& self) } +void insert(Serializer& serializer, const GalileoEphemeris& self) +{ + insert(serializer, self.index); + + insert(serializer, self.count); + + insert(serializer, self.time_of_week); + + insert(serializer, self.week_number); + + insert(serializer, self.satellite_id); + + insert(serializer, self.health); + + insert(serializer, self.iodc); + + insert(serializer, self.iode); + + insert(serializer, self.t_oc); + + insert(serializer, self.af0); + + insert(serializer, self.af1); + + insert(serializer, self.af2); + + insert(serializer, self.t_gd); + + insert(serializer, self.ISC_L1CA); + + insert(serializer, self.ISC_L2C); + + insert(serializer, self.t_oe); + + insert(serializer, self.a); + + insert(serializer, self.a_dot); + + insert(serializer, self.mean_anomaly); + + insert(serializer, self.delta_mean_motion); + + insert(serializer, self.delta_mean_motion_dot); + + insert(serializer, self.eccentricity); + + insert(serializer, self.argument_of_perigee); + + insert(serializer, self.omega); + + insert(serializer, self.omega_dot); + + insert(serializer, self.inclination); + + insert(serializer, self.inclination_dot); + + insert(serializer, self.c_ic); + + insert(serializer, self.c_is); + + insert(serializer, self.c_uc); + + insert(serializer, self.c_us); + + insert(serializer, self.c_rc); + + insert(serializer, self.c_rs); + + insert(serializer, self.valid_flags); + +} +void extract(Serializer& serializer, GalileoEphemeris& self) +{ + extract(serializer, self.index); + + extract(serializer, self.count); + + extract(serializer, self.time_of_week); + + extract(serializer, self.week_number); + + extract(serializer, self.satellite_id); + + extract(serializer, self.health); + + extract(serializer, self.iodc); + + extract(serializer, self.iode); + + extract(serializer, self.t_oc); + + extract(serializer, self.af0); + + extract(serializer, self.af1); + + extract(serializer, self.af2); + + extract(serializer, self.t_gd); + + extract(serializer, self.ISC_L1CA); + + extract(serializer, self.ISC_L2C); + + extract(serializer, self.t_oe); + + extract(serializer, self.a); + + extract(serializer, self.a_dot); + + extract(serializer, self.mean_anomaly); + + extract(serializer, self.delta_mean_motion); + + extract(serializer, self.delta_mean_motion_dot); + + extract(serializer, self.eccentricity); + + extract(serializer, self.argument_of_perigee); + + extract(serializer, self.omega); + + extract(serializer, self.omega_dot); + + extract(serializer, self.inclination); + + extract(serializer, self.inclination_dot); + + extract(serializer, self.c_ic); + + extract(serializer, self.c_is); + + extract(serializer, self.c_uc); + + extract(serializer, self.c_us); + + extract(serializer, self.c_rc); + + extract(serializer, self.c_rs); + + extract(serializer, self.valid_flags); + +} + void insert(Serializer& serializer, const GloEphemeris& self) { insert(serializer, self.index); diff --git a/src/mip/definitions/data_gnss.h b/src/mip/definitions/data_gnss.h index 4e87526ad..c2bb9a258 100644 --- a/src/mip/definitions/data_gnss.h +++ b/src/mip/definitions/data_gnss.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -185,6 +186,7 @@ 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_HORIZONTAL_ACCURACY = 0x0008; ///< 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; struct mip_gnss_pos_llh_data { @@ -205,6 +207,7 @@ bool extract_mip_gnss_pos_llh_data_from_field(const struct mip_field* field, voi 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -218,10 +221,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 = 0x0001; ///< 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; struct mip_gnss_pos_ecef_data { - double x[3]; ///< [meters] + mip_vector3d x; ///< [meters] float x_accuracy; ///< [meters] mip_gnss_pos_ecef_data_valid_flags valid_flags; @@ -234,6 +238,7 @@ bool extract_mip_gnss_pos_ecef_data_from_field(const struct mip_field* field, vo 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -251,10 +256,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_SPEED_ACCURACY = 0x0010; ///< 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; struct mip_gnss_vel_ned_data { - float v[3]; ///< [meters/second] + mip_vector3f v; ///< [meters/second] float speed; ///< [meters/second] float ground_speed; ///< [meters/second] float heading; ///< [degrees] @@ -271,6 +277,7 @@ bool extract_mip_gnss_vel_ned_data_from_field(const struct mip_field* field, voi 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -284,10 +291,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 = 0x0001; ///< 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; struct mip_gnss_vel_ecef_data { - float v[3]; ///< [meters/second] + mip_vector3f v; ///< [meters/second] float v_accuracy; ///< [meters/second] mip_gnss_vel_ecef_data_valid_flags valid_flags; @@ -300,6 +308,7 @@ bool extract_mip_gnss_vel_ecef_data_from_field(const struct mip_field* field, vo 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -318,6 +327,7 @@ static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_TDOP = static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_NDOP = 0x0020; ///< 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; struct mip_gnss_dop_data { @@ -339,6 +349,7 @@ bool extract_mip_gnss_dop_data_from_field(const struct mip_field* field, void* p 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -352,16 +363,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_GNSS_DATE_TIME = 0x0001; ///< 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; struct mip_gnss_utc_time_data { uint16_t year; - uint8_t month; - uint8_t day; - uint8_t hour; - uint8_t min; - uint8_t sec; - uint32_t msec; ///< [Milliseconds] + uint8_t month; ///< Month (1-12) + uint8_t day; ///< Day (1-31) + uint8_t hour; ///< Hour (0-23) + uint8_t min; ///< Minute (0-59) + uint8_t sec; ///< Second (0-59) + uint32_t msec; ///< Millisecond(0-999) mip_gnss_utc_time_data_valid_flags valid_flags; }; @@ -373,6 +385,7 @@ bool extract_mip_gnss_utc_time_data_from_field(const struct mip_field* field, vo 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -386,6 +399,7 @@ 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_TOW = 0x0001; ///< 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; struct mip_gnss_gps_time_data { @@ -402,6 +416,7 @@ bool extract_mip_gnss_gps_time_data_from_field(const struct mip_field* field, vo 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -416,6 +431,7 @@ 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_DRIFT = 0x0002; ///< 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; struct mip_gnss_clock_info_data { @@ -433,6 +449,7 @@ bool extract_mip_gnss_clock_info_data_from_field(const struct mip_field* field, 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -442,18 +459,20 @@ void extract_mip_gnss_clock_info_data_valid_flags(struct mip_serializer* seriali ///@{ 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_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; ///< 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_DNGSS_USED = 0x0002; ///< +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; 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; @@ -461,6 +480,7 @@ 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_NUM_SV = 0x0002; ///< 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; struct mip_gnss_fix_info_data { @@ -484,6 +504,7 @@ void extract_mip_gnss_fix_info_data_fix_flags(struct mip_serializer* serializer, 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -498,6 +519,7 @@ typedef uint16_t mip_gnss_sv_info_data_svflags; static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_NONE = 0x0000; 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; 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; @@ -508,6 +530,7 @@ 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_ELEVATION = 0x0010; ///< 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; struct mip_gnss_sv_info_data { @@ -531,6 +554,7 @@ void extract_mip_gnss_sv_info_data_svflags(struct mip_serializer* serializer, mi 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -562,6 +586,7 @@ 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_STATE = 0x0002; ///< 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; struct mip_gnss_hw_status_data { @@ -588,6 +613,7 @@ void extract_mip_gnss_hw_status_data_antenna_power(struct mip_serializer* serial 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -595,14 +621,14 @@ void extract_mip_gnss_hw_status_data_valid_flags(struct mip_serializer* serializ /// GNSS reported DGNSS status /// ///
Possible Base Station Status Values:
-///
  0 – UDRE Scale Factor = 1.0
-///
  1 – UDRE Scale Factor = 0.75
-///
  2 – UDRE Scale Factor = 0.5
-///
  3 – UDRE Scale Factor = 0.3
-///
  4 – UDRE Scale Factor = 0.2
-///
  5 – UDRE Scale Factor = 0.1
-///
  6 – Reference Station Transmission Not Monitored
-///
  7 – Reference Station Not Working
+///
  0 - UDRE Scale Factor = 1.0
+///
  1 - UDRE Scale Factor = 0.75
+///
  2 - UDRE Scale Factor = 0.5
+///
  3 - UDRE Scale Factor = 0.3
+///
  4 - UDRE Scale Factor = 0.2
+///
  5 - UDRE Scale Factor = 0.1
+///
  6 - Reference Station Transmission Not Monitored
+///
  7 - Reference Station Not Working
/// /// (UDRE = User Differential Range Error) /// @@ -615,6 +641,7 @@ 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_BASE_STATION_STATUS = 0x0004; ///< 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; struct mip_gnss_dgps_info_data { @@ -633,6 +660,7 @@ bool extract_mip_gnss_dgps_info_data_from_field(const struct mip_field* field, v 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -650,6 +678,7 @@ 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_CORRECTION = 0x0004; ///< 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; struct mip_gnss_dgps_channel_data { @@ -668,6 +697,7 @@ bool extract_mip_gnss_dgps_channel_data_from_field(const struct mip_field* field 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -685,6 +715,7 @@ 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_BIAS_ACCURACY = 0x0004; ///< 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; struct mip_gnss_clock_info_2_data { @@ -703,6 +734,7 @@ bool extract_mip_gnss_clock_info_2_data_from_field(const struct mip_field* field 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -714,6 +746,7 @@ void extract_mip_gnss_clock_info_2_data_valid_flags(struct mip_serializer* seria 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; struct mip_gnss_gps_leap_seconds_data { @@ -729,6 +762,7 @@ bool extract_mip_gnss_gps_leap_seconds_data_from_field(const struct mip_field* f 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -743,6 +777,7 @@ 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_CORRECTIONS_AVAILABLE = 0x02; ///< 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; 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; @@ -753,6 +788,7 @@ 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_COUNT = 0x0010; ///< 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; struct mip_gnss_sbas_info_data { @@ -776,6 +812,7 @@ void extract_mip_gnss_sbas_info_data_sbas_status(struct mip_serializer* serializ 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -812,6 +849,7 @@ 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_PSEUDORANGE_CORRECTION = 0x0002; ///< 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; struct mip_gnss_sbas_correction_data { @@ -822,7 +860,7 @@ struct mip_gnss_sbas_correction_data mip_gnss_constellation_id gnss_id; ///< GNSS constellation id uint8_t sv_id; ///< GNSS satellite id within the constellation. uint8_t udrei; ///< [See above 0-13 usable, 14 not monitored, 15 - do not use] - float pseudorange_correction; ///< Pseudorange correction [meters]. + float pseudorange_correction; ///< Pseudo-range correction [meters]. float iono_correction; ///< Ionospheric correction [meters]. mip_gnss_sbas_correction_data_valid_flags valid_flags; @@ -835,6 +873,7 @@ bool extract_mip_gnss_sbas_correction_data_from_field(const struct mip_field* fi 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -867,6 +906,7 @@ 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_JAMMING_STATE = 0x0002; ///< 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; struct mip_gnss_rf_error_detection_data { @@ -894,6 +934,7 @@ void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct mip_serializ 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -915,6 +956,7 @@ 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_BIT1 = 0x0040; ///< 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; 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; @@ -925,12 +967,13 @@ 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_STATION_ID = 0x0010; ///< 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; struct mip_gnss_base_station_info_data { double time_of_week; ///< GPS Time of week the message was received [seconds] uint16_t week_number; ///< GPS Week since 1980 [weeks] - double ecef_pos[3]; ///< Earth-centered, Earth-fixed [m] + mip_vector3d ecef_pos; ///< Earth-centered, Earth-fixed [m] float height; ///< Antenna Height above the marker used in the survey [m] uint16_t station_id; ///< Range: 0-4095 mip_gnss_base_station_info_data_indicator_flags indicators; ///< Bitfield @@ -948,6 +991,7 @@ void extract_mip_gnss_base_station_info_data_indicator_flags(struct mip_serializ 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -966,6 +1010,7 @@ 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_GALILEO_LATENCY = 0x0040; ///< 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; 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; @@ -978,13 +1023,14 @@ 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_GPS_MSM_MESSAGES = 0x0040; ///< Using MSM messages for GPS corrections instead of RTCM messages 1001-1004 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; struct mip_gnss_rtk_corrections_status_data { double time_of_week; ///< GPS Time of week [seconds] uint16_t week_number; ///< GPS Week since 1980 [weeks] mip_gnss_rtk_corrections_status_data_epoch_status epoch_status; ///< Status of the corrections received during this epoch - uint32_t dongle_status; ///< RTK Dongle Status Flags (valid only when using RTK dongle, see MIP_CMD_DESC_RTK_GET_STATUS_FLAGS for details) + uint32_t dongle_status; ///< RTK Dongle Status Flags (valid only when using RTK dongle, see Get RTK Device Status Flags (0x0F,0x01) for details) float gps_correction_latency; ///< Latency of last GPS correction [seconds] float glonass_correction_latency; ///< Latency of last GLONASS correction [seconds] float galileo_correction_latency; ///< Latency of last Galileo correction [seconds] @@ -1004,6 +1050,7 @@ void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct mip_seriali 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1022,6 +1069,7 @@ 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_AZIMUTH = 0x0020; ///< 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; struct mip_gnss_satellite_status_data { @@ -1045,6 +1093,7 @@ bool extract_mip_gnss_satellite_status_data_from_field(const struct mip_field* f 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1080,6 +1129,7 @@ static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_CARRIER static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_DOPPLER_UNCERTAINTY = 0x4000; ///< 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; struct mip_gnss_raw_data { @@ -1094,10 +1144,10 @@ struct mip_gnss_raw_data mip_gnss_signal_id signal_id; ///< Signal identifier for the satellite. float signal_strength; ///< Carrier to noise ratio [dBHz]. mip_gnss_raw_data_gnss_signal_quality quality; ///< Indicator of signal quality. - double pseudorange; ///< Pseudorange measurement [meters]. + double pseudorange; ///< Pseudo-range measurement [meters]. double carrier_phase; ///< Carrier phase measurement [Carrier periods]. float doppler; ///< Measured doppler shift [Hz]. - float range_uncert; ///< Uncertainty of the pseudorange measurement [m]. + float range_uncert; ///< Uncertainty of the pseudo-range measurement [m]. float phase_uncert; ///< Uncertainty of the phase measurement [Carrier periods]. 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. @@ -1115,11 +1165,12 @@ void extract_mip_gnss_raw_data_gnss_signal_quality(struct mip_serializer* serial 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_gnss_gps_ephemeris (0x81,0x61) Gps Ephemeris [C] -/// GPS/Galileo Ephemeris Data +/// GPS Ephemeris Data /// ///@{ @@ -1128,6 +1179,7 @@ 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_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; struct mip_gnss_gps_ephemeris_data { @@ -1148,14 +1200,14 @@ struct mip_gnss_gps_ephemeris_data double ISC_L2C; double t_oe; ///< Reference time for ephemeris in [s]. double a; ///< Semi-major axis [m]. - double a_dot; ///< Semi-matjor axis rate [m/s]. + double a_dot; ///< Semi-major axis rate [m/s]. double mean_anomaly; ///< [rad]. double delta_mean_motion; ///< [rad]. double delta_mean_motion_dot; ///< [rad/s]. double eccentricity; double argument_of_perigee; ///< [rad]. double omega; ///< Longitude of Ascending Node [rad]. - double omega_dot; ///< Rate of Right Ascention [rad/s]. + double omega_dot; ///< Rate of Right Ascension [rad/s]. double inclination; ///< Inclination angle [rad]. double inclination_dot; ///< Inclination angle rate of change [rad/s]. double c_ic; ///< Harmonic Correction Term. @@ -1175,6 +1227,69 @@ bool extract_mip_gnss_gps_ephemeris_data_from_field(const struct mip_field* fiel 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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup c_gnss_galileo_ephemeris (0x81,0x63) Galileo Ephemeris [C] +/// Galileo Ephemeris Data +/// +///@{ + +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; + +struct mip_gnss_galileo_ephemeris_data +{ + uint8_t index; ///< Index of this field in this epoch. + uint8_t count; ///< Total number of fields in this epoch. + double time_of_week; ///< GPS Time of week [seconds] + uint16_t week_number; ///< GPS Week since 1980 [weeks] + uint8_t satellite_id; ///< GNSS satellite id within the constellation. + uint8_t health; ///< Satellite and signal health + uint8_t iodc; ///< Issue of Data Clock. This increments each time the data changes and rolls over at 4. It is used to make sure various raw data elements from different sources line up correctly. + uint8_t iode; ///< Issue of Data Ephemeris. + double t_oc; ///< Reference time for clock data. + double af0; ///< Clock bias in [s]. + 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 t_oe; ///< Reference time for ephemeris in [s]. + double a; ///< Semi-major axis [m]. + double a_dot; ///< Semi-major axis rate [m/s]. + double mean_anomaly; ///< [rad]. + double delta_mean_motion; ///< [rad]. + double delta_mean_motion_dot; ///< [rad/s]. + double eccentricity; + double argument_of_perigee; ///< [rad]. + double omega; ///< Longitude of Ascending Node [rad]. + double omega_dot; ///< Rate of Right Ascension [rad/s]. + double inclination; ///< Inclination angle [rad]. + double inclination_dot; ///< Inclination angle rate of change [rad/s]. + double c_ic; ///< Harmonic Correction Term. + double c_is; ///< Harmonic Correction Term. + double c_uc; ///< Harmonic Correction Term. + double c_us; ///< Harmonic Correction Term. + 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(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); +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); + + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1187,6 +1302,7 @@ typedef uint16_t mip_gnss_glo_ephemeris_data_valid_flags; static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA_VALID_FLAGS_NONE = 0x0000; 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; struct mip_gnss_glo_ephemeris_data { @@ -1199,11 +1315,11 @@ struct mip_gnss_glo_ephemeris_data uint32_t tk; ///< Frame start time within current day [seconds] uint32_t tb; ///< Ephemeris reference time [seconds] uint8_t sat_type; ///< Type of satellite (M) GLONASS = 0, GLONASS-M = 1 - double gamma; ///< Relative deviation of carrier frequency from nominal [dimesnionless] + double gamma; ///< Relative deviation of carrier frequency from nominal [dimensionless] double tau_n; ///< Time correction relative to GLONASS Time [seconds] - double x[3]; ///< Satellite PE-90 position [m] - float v[3]; ///< Satellite PE-90 velocity [m/s] - float a[3]; ///< Satellite PE-90 acceleration due to pertubations [m/s^2] + mip_vector3d x; ///< Satellite PE-90 position [m] + mip_vector3f v; ///< Satellite PE-90 velocity [m/s] + mip_vector3f a; ///< Satellite PE-90 acceleration due to perturbations [m/s^2] uint8_t health; ///< Satellite Health (Bn), Non-zero indicates satellite malfunction uint8_t P; ///< Satellite operation mode (See GLONASS ICD) uint8_t NT; ///< Day number within a 4 year period. @@ -1225,6 +1341,7 @@ bool extract_mip_gnss_glo_ephemeris_data_from_field(const struct mip_field* fiel 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1240,6 +1357,7 @@ 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_ALPHA = 0x0004; ///< 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; struct mip_gnss_gps_iono_corr_data { @@ -1258,6 +1376,7 @@ bool extract_mip_gnss_gps_iono_corr_data_from_field(const struct mip_field* fiel 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1273,12 +1392,13 @@ 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_ALPHA = 0x0004; ///< 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; struct mip_gnss_galileo_iono_corr_data { double time_of_week; ///< GPS Time of week [seconds] uint16_t week_number; ///< GPS Week since 1980 [weeks] - double alpha[3]; ///< Coefficients for the model. + 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; @@ -1291,6 +1411,7 @@ bool extract_mip_gnss_galileo_iono_corr_data_from_field(const struct mip_field* 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); + ///@} /// diff --git a/src/mip/definitions/data_gnss.hpp b/src/mip/definitions/data_gnss.hpp index 199554912..70b783529 100644 --- a/src/mip/definitions/data_gnss.hpp +++ b/src/mip/definitions/data_gnss.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -67,11 +68,11 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -static const uint8_t MIP_GNSS1_DATA_DESC_SET = 0x91; -static const uint8_t MIP_GNSS2_DATA_DESC_SET = 0x92; -static const uint8_t MIP_GNSS3_DATA_DESC_SET = 0x93; -static const uint8_t MIP_GNSS4_DATA_DESC_SET = 0x94; -static const uint8_t MIP_GNSS5_DATA_DESC_SET = 0x95; +static constexpr const uint8_t MIP_GNSS1_DATA_DESC_SET = 0x91; +static constexpr const uint8_t MIP_GNSS2_DATA_DESC_SET = 0x92; +static constexpr const uint8_t MIP_GNSS3_DATA_DESC_SET = 0x93; +static constexpr const uint8_t MIP_GNSS4_DATA_DESC_SET = 0x94; +static constexpr const uint8_t MIP_GNSS5_DATA_DESC_SET = 0x95; enum class GnssConstellationId : uint8_t { UNKNOWN = 0, ///< @@ -160,8 +161,8 @@ enum class SbasSystem : uint8_t GAGAN = 4, ///< }; -static const uint32_t GNSS_DGPS_INFO_MAX_CHANNEL_NUMBER = 32; -static const uint32_t GNSS_SV_INFO_MAX_SV_NUMBER = 32; +static constexpr const uint32_t GNSS_DGPS_INFO_MAX_CHANNEL_NUMBER = 32; +static constexpr const uint32_t GNSS_SV_INFO_MAX_SV_NUMBER = 32; //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -175,11 +176,6 @@ static const uint32_t GNSS_SV_INFO_MAX_SV_NUMBER = 32; struct PosLlh { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_POSITION_LLH; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -191,6 +187,7 @@ struct PosLlh HORIZONTAL_ACCURACY = 0x0008, ///< VERTICAL_ACCURACY = 0x0010, ///< FLAGS = 0x001F, ///< + ALL = 0x001F, }; uint16_t value = NONE; @@ -198,9 +195,25 @@ struct PosLlh ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double latitude = 0; ///< [degrees] @@ -211,10 +224,27 @@ struct PosLlh float vertical_accuracy = 0; ///< [meters] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(latitude,longitude,ellipsoid_height,msl_height,horizontal_accuracy,vertical_accuracy,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -225,11 +255,6 @@ void extract(Serializer& serializer, PosLlh& self); struct PosEcef { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_POSITION_ECEF; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -238,6 +263,7 @@ struct PosEcef POSITION = 0x0001, ///< POSITION_ACCURACY = 0x0002, ///< FLAGS = 0x0003, ///< + ALL = 0x0003, }; uint16_t value = NONE; @@ -245,19 +271,46 @@ struct PosEcef ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; - double x[3] = {0}; ///< [meters] + Vector3d x; ///< [meters] float x_accuracy = 0; ///< [meters] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(x[0],x[1],x[2],x_accuracy,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -268,11 +321,6 @@ void extract(Serializer& serializer, PosEcef& self); struct VelNed { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_VELOCITY_NED; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -285,6 +333,7 @@ struct VelNed SPEED_ACCURACY = 0x0010, ///< HEADING_ACCURACY = 0x0020, ///< FLAGS = 0x003F, ///< + ALL = 0x003F, }; uint16_t value = NONE; @@ -292,12 +341,30 @@ struct VelNed ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; - float v[3] = {0}; ///< [meters/second] + Vector3f v; ///< [meters/second] float speed = 0; ///< [meters/second] float ground_speed = 0; ///< [meters/second] float heading = 0; ///< [degrees] @@ -305,10 +372,27 @@ struct VelNed float heading_accuracy = 0; ///< [degrees] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(v[0],v[1],v[2],speed,ground_speed,heading,speed_accuracy,heading_accuracy,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -319,11 +403,6 @@ void extract(Serializer& serializer, VelNed& self); struct VelEcef { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_VELOCITY_ECEF; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -332,6 +411,7 @@ struct VelEcef VELOCITY = 0x0001, ///< VELOCITY_ACCURACY = 0x0002, ///< FLAGS = 0x0003, ///< + ALL = 0x0003, }; uint16_t value = NONE; @@ -339,19 +419,46 @@ struct VelEcef ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; - float v[3] = {0}; ///< [meters/second] + Vector3f v; ///< [meters/second] float v_accuracy = 0; ///< [meters/second] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(v[0],v[1],v[2],v_accuracy,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -362,11 +469,6 @@ void extract(Serializer& serializer, VelEcef& self); struct Dop { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_DOP; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -380,6 +482,7 @@ struct Dop NDOP = 0x0020, ///< EDOP = 0x0040, ///< FLAGS = 0x007F, ///< + ALL = 0x007F, }; uint16_t value = NONE; @@ -387,9 +490,29 @@ struct Dop ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; float gdop = 0; ///< Geometric DOP @@ -401,10 +524,27 @@ struct Dop float edop = 0; ///< Easting DOP ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(gdop,pdop,hdop,vdop,tdop,ndop,edop,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -415,11 +555,6 @@ void extract(Serializer& serializer, Dop& self); struct UtcTime { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_UTC_TIME; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -428,6 +563,7 @@ struct UtcTime GNSS_DATE_TIME = 0x0001, ///< LEAP_SECONDS_KNOWN = 0x0002, ///< FLAGS = 0x0003, ///< + ALL = 0x0003, }; uint16_t value = NONE; @@ -435,24 +571,51 @@ struct UtcTime ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint16_t year = 0; - uint8_t month = 0; - uint8_t day = 0; - uint8_t hour = 0; - uint8_t min = 0; - uint8_t sec = 0; - uint32_t msec = 0; ///< [Milliseconds] + uint8_t month = 0; ///< Month (1-12) + uint8_t day = 0; ///< Day (1-31) + uint8_t hour = 0; ///< Hour (0-23) + uint8_t min = 0; ///< Minute (0-59) + uint8_t sec = 0; ///< Second (0-59) + uint32_t msec = 0; ///< Millisecond(0-999) ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(year,month,day,hour,min,sec,msec,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -463,11 +626,6 @@ void extract(Serializer& serializer, UtcTime& self); struct GpsTime { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_TIME; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -476,6 +634,7 @@ struct GpsTime TOW = 0x0001, ///< WEEK_NUMBER = 0x0002, ///< FLAGS = 0x0003, ///< + ALL = 0x0003, }; uint16_t value = NONE; @@ -483,19 +642,46 @@ struct GpsTime ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double tow = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(tow,week_number,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -506,11 +692,6 @@ void extract(Serializer& serializer, GpsTime& self); struct ClockInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_CLOCK_INFO; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -520,6 +701,7 @@ struct ClockInfo DRIFT = 0x0002, ///< ACCURACY_ESTIMATE = 0x0004, ///< FLAGS = 0x0007, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -527,9 +709,21 @@ struct ClockInfo ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double bias = 0; ///< [seconds] @@ -537,10 +731,27 @@ struct ClockInfo double accuracy_estimate = 0; ///< [seconds] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(bias,drift,accuracy_estimate,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -551,20 +762,16 @@ void extract(Serializer& serializer, ClockInfo& self); struct FixInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_FIX_INFO; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class FixType : uint8_t { - FIX_3D = 0, ///< - FIX_2D = 1, ///< - FIX_TIME_ONLY = 2, ///< - FIX_NONE = 3, ///< - FIX_INVALID = 4, ///< - FIX_RTK_FLOAT = 5, ///< - FIX_RTK_FIXED = 6, ///< + FIX_3D = 0, ///< + FIX_2D = 1, ///< + FIX_TIME_ONLY = 2, ///< + FIX_NONE = 3, ///< + FIX_INVALID = 4, ///< + FIX_RTK_FLOAT = 5, ///< + FIX_RTK_FIXED = 6, ///< + FIX_DIFFERENTIAL = 7, ///< }; struct FixFlags : Bitfield @@ -573,7 +780,8 @@ struct FixInfo { NONE = 0x0000, SBAS_USED = 0x0001, ///< - DNGSS_USED = 0x0002, ///< + DGNSS_USED = 0x0002, ///< + ALL = 0x0003, }; uint16_t value = NONE; @@ -581,9 +789,17 @@ struct FixInfo FixFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } FixFlags& operator=(uint16_t val) { value = val; return *this; } - FixFlags& operator=(int val) { value = val; return *this; } + FixFlags& operator=(int val) { value = uint16_t(val); return *this; } 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 @@ -595,6 +811,7 @@ struct FixInfo NUM_SV = 0x0002, ///< FIX_FLAGS = 0x0004, ///< FLAGS = 0x0007, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -602,9 +819,21 @@ struct FixInfo ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; FixType fix_type = static_cast(0); @@ -612,10 +841,27 @@ struct FixInfo FixFlags fix_flags; ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(fix_type,num_sv,fix_flags,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -628,11 +874,6 @@ void extract(Serializer& serializer, FixInfo& self); struct SvInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SV_INFO; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct SVFlags : Bitfield { enum _enumType : uint16_t @@ -640,6 +881,7 @@ struct SvInfo NONE = 0x0000, USED_FOR_NAVIGATION = 0x0001, ///< HEALTHY = 0x0002, ///< + ALL = 0x0003, }; uint16_t value = NONE; @@ -647,9 +889,17 @@ struct SvInfo SVFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } SVFlags& operator=(uint16_t val) { value = val; return *this; } - SVFlags& operator=(int val) { value = val; return *this; } + SVFlags& operator=(int val) { value = uint16_t(val); return *this; } 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 @@ -664,6 +914,7 @@ struct SvInfo ELEVATION = 0x0010, ///< SV_FLAGS = 0x0020, ///< FLAGS = 0x003F, ///< + ALL = 0x003F, }; uint16_t value = NONE; @@ -671,9 +922,27 @@ struct SvInfo ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t channel = 0; ///< Receiver channel number @@ -684,10 +953,27 @@ struct SvInfo SVFlags sv_flags; ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(channel,sv_id,carrier_noise_ratio,azimuth,elevation,sv_flags,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -698,11 +984,6 @@ void extract(Serializer& serializer, SvInfo& self); struct HwStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_HW_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class ReceiverState : uint8_t { OFF = 0, ///< @@ -735,6 +1016,7 @@ struct HwStatus ANTENNA_STATE = 0x0002, ///< ANTENNA_POWER = 0x0004, ///< FLAGS = 0x0007, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -742,9 +1024,21 @@ struct HwStatus ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; ReceiverState receiver_state = static_cast(0); @@ -752,10 +1046,27 @@ struct HwStatus AntennaPower antenna_power = static_cast(0); ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(receiver_state,antenna_state,antenna_power,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -763,14 +1074,14 @@ void extract(Serializer& serializer, HwStatus& self); /// GNSS reported DGNSS status /// ///
Possible Base Station Status Values:
-///
  0 – UDRE Scale Factor = 1.0
-///
  1 – UDRE Scale Factor = 0.75
-///
  2 – UDRE Scale Factor = 0.5
-///
  3 – UDRE Scale Factor = 0.3
-///
  4 – UDRE Scale Factor = 0.2
-///
  5 – UDRE Scale Factor = 0.1
-///
  6 – Reference Station Transmission Not Monitored
-///
  7 – Reference Station Not Working
+///
  0 - UDRE Scale Factor = 1.0
+///
  1 - UDRE Scale Factor = 0.75
+///
  2 - UDRE Scale Factor = 0.5
+///
  3 - UDRE Scale Factor = 0.3
+///
  4 - UDRE Scale Factor = 0.2
+///
  5 - UDRE Scale Factor = 0.1
+///
  6 - Reference Station Transmission Not Monitored
+///
  7 - Reference Station Not Working
/// /// (UDRE = User Differential Range Error) /// @@ -778,11 +1089,6 @@ void extract(Serializer& serializer, HwStatus& self); struct DgpsInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_DGPS_INFO; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -793,6 +1099,7 @@ struct DgpsInfo BASE_STATION_STATUS = 0x0004, ///< NUM_CHANNELS = 0x0008, ///< FLAGS = 0x000F, ///< + ALL = 0x000F, }; uint16_t value = NONE; @@ -800,9 +1107,23 @@ struct DgpsInfo ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t sv_id = 0; @@ -811,10 +1132,27 @@ struct DgpsInfo float range_rate_correction = 0; ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(sv_id,age,range_correction,range_rate_correction,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -827,11 +1165,6 @@ void extract(Serializer& serializer, DgpsInfo& self); struct DgpsChannel { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_DGPS_CHANNEL_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -842,6 +1175,7 @@ struct DgpsChannel RANGE_CORRECTION = 0x0004, ///< RANGE_RATE_CORRECTION = 0x0008, ///< FLAGS = 0x000F, ///< + ALL = 0x000F, }; uint16_t value = NONE; @@ -849,9 +1183,23 @@ struct DgpsChannel ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t sv_id = 0; @@ -860,10 +1208,27 @@ struct DgpsChannel float range_rate_correction = 0; ///< [m/s] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(sv_id,age,range_correction,range_rate_correction,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -876,11 +1241,6 @@ void extract(Serializer& serializer, DgpsChannel& self); struct ClockInfo2 { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_CLOCK_INFO_2; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -891,6 +1251,7 @@ struct ClockInfo2 BIAS_ACCURACY = 0x0004, ///< DRIFT_ACCURACY = 0x0008, ///< FLAGS = 0x000F, ///< + ALL = 0x000F, }; uint16_t value = NONE; @@ -898,9 +1259,23 @@ struct ClockInfo2 ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double bias = 0; @@ -909,10 +1284,27 @@ struct ClockInfo2 double drift_accuracy_estimate = 0; ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(bias,drift,bias_accuracy_estimate,drift_accuracy_estimate,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -923,17 +1315,13 @@ void extract(Serializer& serializer, ClockInfo2& self); struct GpsLeapSeconds { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_LEAP_SECONDS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t { NONE = 0x0000, LEAP_SECONDS = 0x0002, ///< + ALL = 0x0002, }; uint16_t value = NONE; @@ -941,18 +1329,41 @@ struct GpsLeapSeconds ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t leap_seconds = 0; ///< [s] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(leap_seconds,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -963,11 +1374,6 @@ void extract(Serializer& serializer, GpsLeapSeconds& self); struct SbasInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SBAS_INFO; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct SbasStatus : Bitfield { enum _enumType : uint8_t @@ -977,6 +1383,7 @@ struct SbasInfo CORRECTIONS_AVAILABLE = 0x02, ///< INTEGRITY_AVAILABLE = 0x04, ///< TEST_MODE = 0x08, ///< + ALL = 0x0F, }; uint8_t value = NONE; @@ -984,9 +1391,21 @@ struct SbasInfo SbasStatus(int val) : value((uint8_t)val) {} operator uint8_t() const { return value; } SbasStatus& operator=(uint8_t val) { value = val; return *this; } - SbasStatus& operator=(int val) { value = val; return *this; } + SbasStatus& operator=(int val) { value = uint8_t(val); return *this; } 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 @@ -1001,6 +1420,7 @@ struct SbasInfo COUNT = 0x0010, ///< SBAS_STATUS = 0x0020, ///< FLAGS = 0x003F, ///< + ALL = 0x003F, }; uint16_t value = NONE; @@ -1008,9 +1428,27 @@ struct SbasInfo ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double time_of_week = 0; ///< GPS Time of week [seconds] @@ -1021,10 +1459,27 @@ struct SbasInfo SbasStatus sbas_status; ///< Status of the SBAS service ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_of_week,week_number,sbas_system,sbas_id,count,sbas_status,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1057,11 +1512,6 @@ void extract(Serializer& serializer, SbasInfo& self); struct SbasCorrection { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SBAS_CORRECTION; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -1071,6 +1521,7 @@ struct SbasCorrection PSEUDORANGE_CORRECTION = 0x0002, ///< IONO_CORRECTION = 0x0004, ///< FLAGS = 0x0007, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -1078,9 +1529,21 @@ struct SbasCorrection ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t index = 0; ///< Index of this field in this epoch. @@ -1090,14 +1553,31 @@ struct SbasCorrection GnssConstellationId gnss_id = static_cast(0); ///< GNSS constellation id uint8_t sv_id = 0; ///< GNSS satellite id within the constellation. uint8_t udrei = 0; ///< [See above 0-13 usable, 14 not monitored, 15 - do not use] - float pseudorange_correction = 0; ///< Pseudorange correction [meters]. + float pseudorange_correction = 0; ///< Pseudo-range correction [meters]. float iono_correction = 0; ///< Ionospheric correction [meters]. ValidFlags valid_flags; + 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"; + + + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1108,11 +1588,6 @@ void extract(Serializer& serializer, SbasCorrection& self); struct RfErrorDetection { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_RF_ERROR_DETECTION; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class RFBand : uint8_t { UNKNOWN = 0, ///< @@ -1146,6 +1621,7 @@ struct RfErrorDetection JAMMING_STATE = 0x0002, ///< SPOOFING_STATE = 0x0004, ///< FLAGS = 0x0007, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -1153,9 +1629,21 @@ struct RfErrorDetection ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; RFBand rf_band = static_cast(0); ///< RF Band of the reported information @@ -1164,10 +1652,27 @@ struct RfErrorDetection uint8_t reserved[4] = {0}; ///< Reserved for future use ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(rf_band,jamming_state,spoofing_state,reserved,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1180,11 +1685,6 @@ void extract(Serializer& serializer, RfErrorDetection& self); struct BaseStationInfo { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_BASE_STATION_INFO; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct IndicatorFlags : Bitfield { enum _enumType : uint16_t @@ -1199,6 +1699,7 @@ struct BaseStationInfo QUARTER_CYCLE_BIT1 = 0x0040, ///< QUARTER_CYCLE_BIT2 = 0x0080, ///< QUARTER_CYCLE_BITS = 0x00C0, ///< + ALL = 0x00FF, }; uint16_t value = NONE; @@ -1206,9 +1707,31 @@ struct BaseStationInfo IndicatorFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } IndicatorFlags& operator=(uint16_t val) { value = val; return *this; } - IndicatorFlags& operator=(int val) { value = val; return *this; } + IndicatorFlags& operator=(int val) { value = uint16_t(val); return *this; } 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 @@ -1223,6 +1746,7 @@ struct BaseStationInfo STATION_ID = 0x0010, ///< INDICATORS = 0x0020, ///< FLAGS = 0x003F, ///< + ALL = 0x003F, }; uint16_t value = NONE; @@ -1230,23 +1754,58 @@ struct BaseStationInfo ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double time_of_week = 0; ///< GPS Time of week the message was received [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] - double ecef_pos[3] = {0}; ///< Earth-centered, Earth-fixed [m] + Vector3d ecef_pos; ///< Earth-centered, Earth-fixed [m] float height = 0; ///< Antenna Height above the marker used in the survey [m] uint16_t station_id = 0; ///< Range: 0-4095 IndicatorFlags indicators; ///< Bitfield ValidFlags valid_flags; + 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"; + + + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1256,11 +1815,6 @@ void extract(Serializer& serializer, BaseStationInfo& self); struct RtkCorrectionsStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_RTK_CORRECTIONS_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -1275,6 +1829,7 @@ struct RtkCorrectionsStatus GALILEO_LATENCY = 0x0040, ///< BEIDOU_LATENCY = 0x0080, ///< FLAGS = 0x00FF, ///< + ALL = 0x00FF, }; uint16_t value = NONE; @@ -1282,9 +1837,31 @@ struct RtkCorrectionsStatus ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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 @@ -1301,6 +1878,7 @@ struct RtkCorrectionsStatus USING_GPS_MSM_MESSAGES = 0x0040, ///< Using MSM messages for GPS corrections instead of RTCM messages 1001-1004 USING_GLONASS_MSM_MESSAGES = 0x0080, ///< Using MSM messages for GLONASS corrections instead of RTCM messages 1009-1012 DONGLE_STATUS_READ_FAILED = 0x0100, ///< A read of the dongle status was attempted, but failed + ALL = 0x01FF, }; uint16_t value = NONE; @@ -1308,15 +1886,37 @@ struct RtkCorrectionsStatus EpochStatus(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } EpochStatus& operator=(uint16_t val) { value = val; return *this; } - EpochStatus& operator=(int val) { value = val; return *this; } + EpochStatus& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; 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 - uint32_t dongle_status = 0; ///< RTK Dongle Status Flags (valid only when using RTK dongle, see MIP_CMD_DESC_RTK_GET_STATUS_FLAGS for details) + uint32_t dongle_status = 0; ///< RTK Dongle Status Flags (valid only when using RTK dongle, see Get RTK Device Status Flags (0x0F,0x01) for details) float gps_correction_latency = 0; ///< Latency of last GPS correction [seconds] float glonass_correction_latency = 0; ///< Latency of last GLONASS correction [seconds] float galileo_correction_latency = 0; ///< Latency of last Galileo correction [seconds] @@ -1324,10 +1924,27 @@ struct RtkCorrectionsStatus uint32_t reserved[4] = {0}; ///< Reserved for future use ValidFlags valid_flags; + 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"; + + + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1338,11 +1955,6 @@ void extract(Serializer& serializer, RtkCorrectionsStatus& self); struct SatelliteStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SATELLITE_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -1356,6 +1968,7 @@ struct SatelliteStatus AZIMUTH = 0x0020, ///< HEALTH = 0x0040, ///< FLAGS = 0x007F, ///< + ALL = 0x007F, }; uint16_t value = NONE; @@ -1363,9 +1976,29 @@ struct SatelliteStatus ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t index = 0; ///< Index of this field in this epoch. @@ -1379,10 +2012,27 @@ struct SatelliteStatus bool health = 0; ///< True if the satellite is healthy. ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(index,count,time_of_week,week_number,gnss_id,satellite_id,elevation,azimuth,health,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1393,11 +2043,6 @@ void extract(Serializer& serializer, SatelliteStatus& self); struct Raw { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_RAW; - - static const bool HAS_FUNCTION_SELECTOR = false; - enum class GnssSignalQuality : uint8_t { NONE = 0, ///< @@ -1430,6 +2075,7 @@ struct Raw DOPPLER_UNCERTAINTY = 0x4000, ///< LOCK_TIME = 0x8000, ///< FLAGS = 0xFFFF, ///< + ALL = 0xFFFF, }; uint16_t value = NONE; @@ -1437,9 +2083,47 @@ struct Raw ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t index = 0; ///< Index of this field in this epoch. @@ -1453,34 +2137,46 @@ struct Raw GnssSignalId signal_id = static_cast(0); ///< Signal identifier for the satellite. float signal_strength = 0; ///< Carrier to noise ratio [dBHz]. GnssSignalQuality quality = static_cast(0); ///< Indicator of signal quality. - double pseudorange = 0; ///< Pseudorange measurement [meters]. + double pseudorange = 0; ///< Pseudo-range measurement [meters]. double carrier_phase = 0; ///< Carrier phase measurement [Carrier periods]. float doppler = 0; ///< Measured doppler shift [Hz]. - float range_uncert = 0; ///< Uncertainty of the pseudorange measurement [m]. + float range_uncert = 0; ///< Uncertainty of the pseudo-range measurement [m]. float phase_uncert = 0; ///< Uncertainty of the phase measurement [Carrier periods]. float doppler_uncert = 0; ///< Uncertainty of the measured doppler shift [Hz]. float lock_time = 0; ///< DOC Minimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver. ValidFlags valid_flags; + 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"; + + + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_gnss_gps_ephemeris (0x81,0x61) Gps Ephemeris [CPP] -/// GPS/Galileo Ephemeris Data +/// GPS Ephemeris Data /// ///@{ struct GpsEphemeris { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_EPHEMERIS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -1489,6 +2185,7 @@ struct GpsEphemeris EPHEMERIS = 0x0001, ///< MODERN_DATA = 0x0002, ///< FLAGS = 0x0003, ///< + ALL = 0x0003, }; uint16_t value = NONE; @@ -1496,9 +2193,19 @@ struct GpsEphemeris ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t index = 0; ///< Index of this field in this epoch. @@ -1518,14 +2225,14 @@ struct GpsEphemeris double ISC_L2C = 0; double t_oe = 0; ///< Reference time for ephemeris in [s]. double a = 0; ///< Semi-major axis [m]. - double a_dot = 0; ///< Semi-matjor axis rate [m/s]. + double a_dot = 0; ///< Semi-major axis rate [m/s]. double mean_anomaly = 0; ///< [rad]. double delta_mean_motion = 0; ///< [rad]. double delta_mean_motion_dot = 0; ///< [rad/s]. double eccentricity = 0; double argument_of_perigee = 0; ///< [rad]. double omega = 0; ///< Longitude of Ascending Node [rad]. - double omega_dot = 0; ///< Rate of Right Ascention [rad/s]. + double omega_dot = 0; ///< Rate of Right Ascension [rad/s]. double inclination = 0; ///< Inclination angle [rad]. double inclination_dot = 0; ///< Inclination angle rate of change [rad/s]. double c_ic = 0; ///< Harmonic Correction Term. @@ -1536,10 +2243,124 @@ struct GpsEphemeris double c_rs = 0; ///< Harmonic Correction Term. ValidFlags valid_flags; + 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"; + + + auto as_tuple() 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() + { + 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); + +///@} +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup cpp_gnss_galileo_ephemeris (0x81,0x63) Galileo Ephemeris [CPP] +/// Galileo Ephemeris Data +/// +///@{ + +struct GalileoEphemeris +{ + struct ValidFlags : Bitfield + { + enum _enumType : uint16_t + { + NONE = 0x0000, + EPHEMERIS = 0x0001, ///< + MODERN_DATA = 0x0002, ///< + FLAGS = 0x0003, ///< + ALL = 0x0003, + }; + uint16_t value = NONE; + + ValidFlags() : value(NONE) {} + ValidFlags(int val) : value((uint16_t)val) {} + operator uint16_t() const { return value; } + ValidFlags& operator=(uint16_t val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } + 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; } + }; + + 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] + uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] + uint8_t satellite_id = 0; ///< GNSS satellite id within the constellation. + uint8_t health = 0; ///< Satellite and signal health + uint8_t iodc = 0; ///< Issue of Data Clock. This increments each time the data changes and rolls over at 4. It is used to make sure various raw data elements from different sources line up correctly. + uint8_t iode = 0; ///< Issue of Data Ephemeris. + double t_oc = 0; ///< Reference time for clock data. + double af0 = 0; ///< Clock bias in [s]. + 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 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]. + double mean_anomaly = 0; ///< [rad]. + double delta_mean_motion = 0; ///< [rad]. + double delta_mean_motion_dot = 0; ///< [rad/s]. + double eccentricity = 0; + double argument_of_perigee = 0; ///< [rad]. + double omega = 0; ///< Longitude of Ascending Node [rad]. + double omega_dot = 0; ///< Rate of Right Ascension [rad/s]. + double inclination = 0; ///< Inclination angle [rad]. + double inclination_dot = 0; ///< Inclination angle rate of change [rad/s]. + double c_ic = 0; ///< Harmonic Correction Term. + double c_is = 0; ///< Harmonic Correction Term. + double c_uc = 0; ///< Harmonic Correction Term. + double c_us = 0; ///< Harmonic Correction Term. + double c_rc = 0; ///< Harmonic Correction Term. + double c_rs = 0; ///< Harmonic Correction Term. + ValidFlags valid_flags; + + 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"; + + + auto as_tuple() 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() + { + 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); + + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1550,11 +2371,6 @@ void extract(Serializer& serializer, GpsEphemeris& self); struct GloEphemeris { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GLONASS_EPHEMERIS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -1562,6 +2378,7 @@ struct GloEphemeris NONE = 0x0000, EPHEMERIS = 0x0001, ///< FLAGS = 0x0001, ///< + ALL = 0x0001, }; uint16_t value = NONE; @@ -1569,9 +2386,17 @@ struct GloEphemeris ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint8_t index = 0; ///< Index of this field in this epoch. @@ -1583,11 +2408,11 @@ struct GloEphemeris uint32_t tk = 0; ///< Frame start time within current day [seconds] uint32_t tb = 0; ///< Ephemeris reference time [seconds] uint8_t sat_type = 0; ///< Type of satellite (M) GLONASS = 0, GLONASS-M = 1 - double gamma = 0; ///< Relative deviation of carrier frequency from nominal [dimesnionless] + double gamma = 0; ///< Relative deviation of carrier frequency from nominal [dimensionless] double tau_n = 0; ///< Time correction relative to GLONASS Time [seconds] - double x[3] = {0}; ///< Satellite PE-90 position [m] - float v[3] = {0}; ///< Satellite PE-90 velocity [m/s] - float a[3] = {0}; ///< Satellite PE-90 acceleration due to pertubations [m/s^2] + Vector3d x; ///< Satellite PE-90 position [m] + Vector3f v; ///< Satellite PE-90 velocity [m/s] + Vector3f a; ///< Satellite PE-90 acceleration due to perturbations [m/s^2] uint8_t health = 0; ///< Satellite Health (Bn), Non-zero indicates satellite malfunction uint8_t P = 0; ///< Satellite operation mode (See GLONASS ICD) uint8_t NT = 0; ///< Day number within a 4 year period. @@ -1600,10 +2425,27 @@ struct GloEphemeris uint8_t P4 = 0; ///< Flag indicating ephemeris parameters are present ValidFlags valid_flags; + 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"; + + + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1614,11 +2456,6 @@ void extract(Serializer& serializer, GloEphemeris& self); struct GpsIonoCorr { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_IONO_CORR; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -1629,6 +2466,7 @@ struct GpsIonoCorr ALPHA = 0x0004, ///< BETA = 0x0008, ///< FLAGS = 0x000F, ///< + ALL = 0x000F, }; uint16_t value = NONE; @@ -1636,9 +2474,23 @@ struct GpsIonoCorr ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double time_of_week = 0; ///< GPS Time of week [seconds] @@ -1647,10 +2499,27 @@ struct GpsIonoCorr double beta[4] = {0}; ///< Ionospheric Correction Terms. ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_of_week,week_number,alpha,beta,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -1661,11 +2530,6 @@ void extract(Serializer& serializer, GpsIonoCorr& self); struct GalileoIonoCorr { - static const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GALILEO_IONO_CORR; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -1676,6 +2540,7 @@ struct GalileoIonoCorr ALPHA = 0x0004, ///< DISTURBANCE_FLAGS = 0x0008, ///< FLAGS = 0x000F, ///< + ALL = 0x000F, }; uint16_t value = NONE; @@ -1683,21 +2548,52 @@ struct GalileoIonoCorr ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double time_of_week = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] - double alpha[3] = {0}; ///< Coefficients for the model. + Vector3d alpha; ///< Coefficients for the model. uint8_t disturbance_flags = 0; ///< Region disturbance flags (bits 1-5). ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_of_week,week_number,alpha[0],alpha[1],alpha[2],disturbance_flags,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// diff --git a/src/mip/definitions/data_sensor.h b/src/mip/definitions/data_sensor.h index 0ca5dc02b..bae38d0a0 100644 --- a/src/mip/definitions/data_sensor.h +++ b/src/mip/definitions/data_sensor.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -79,7 +80,7 @@ enum struct mip_sensor_raw_accel_data { - float raw_accel[3]; ///< Native sensor counts + mip_vector3f raw_accel; ///< Native sensor counts }; typedef struct mip_sensor_raw_accel_data mip_sensor_raw_accel_data; @@ -87,6 +88,7 @@ void insert_mip_sensor_raw_accel_data(struct mip_serializer* serializer, const m void extract_mip_sensor_raw_accel_data(struct mip_serializer* serializer, mip_sensor_raw_accel_data* self); bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -98,7 +100,7 @@ bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field* field, struct mip_sensor_raw_gyro_data { - float raw_gyro[3]; ///< Native sensor counts + mip_vector3f raw_gyro; ///< Native sensor counts }; typedef struct mip_sensor_raw_gyro_data mip_sensor_raw_gyro_data; @@ -106,6 +108,7 @@ void insert_mip_sensor_raw_gyro_data(struct mip_serializer* serializer, const mi void extract_mip_sensor_raw_gyro_data(struct mip_serializer* serializer, mip_sensor_raw_gyro_data* self); bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -117,7 +120,7 @@ bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field* field, struct mip_sensor_raw_mag_data { - float raw_mag[3]; ///< Native sensor counts + mip_vector3f raw_mag; ///< Native sensor counts }; typedef struct mip_sensor_raw_mag_data mip_sensor_raw_mag_data; @@ -125,6 +128,7 @@ void insert_mip_sensor_raw_mag_data(struct mip_serializer* serializer, const mip void extract_mip_sensor_raw_mag_data(struct mip_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,6 +148,7 @@ void insert_mip_sensor_raw_pressure_data(struct mip_serializer* serializer, cons void extract_mip_sensor_raw_pressure_data(struct mip_serializer* serializer, mip_sensor_raw_pressure_data* self); bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -155,7 +160,7 @@ bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field* fie struct mip_sensor_scaled_accel_data { - float scaled_accel[3]; ///< (x, y, z)[g] + mip_vector3f scaled_accel; ///< (x, y, z)[g] }; typedef struct mip_sensor_scaled_accel_data mip_sensor_scaled_accel_data; @@ -163,6 +168,7 @@ void insert_mip_sensor_scaled_accel_data(struct mip_serializer* serializer, cons void extract_mip_sensor_scaled_accel_data(struct mip_serializer* serializer, mip_sensor_scaled_accel_data* self); bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -174,7 +180,7 @@ bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field* fie struct mip_sensor_scaled_gyro_data { - float scaled_gyro[3]; ///< (x, y, z) [radians/second] + mip_vector3f scaled_gyro; ///< (x, y, z) [radians/second] }; typedef struct mip_sensor_scaled_gyro_data mip_sensor_scaled_gyro_data; @@ -182,6 +188,7 @@ void insert_mip_sensor_scaled_gyro_data(struct mip_serializer* serializer, const void extract_mip_sensor_scaled_gyro_data(struct mip_serializer* serializer, mip_sensor_scaled_gyro_data* self); bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -193,7 +200,7 @@ bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field* fiel struct mip_sensor_scaled_mag_data { - float scaled_mag[3]; ///< (x, y, z) [Gauss] + mip_vector3f scaled_mag; ///< (x, y, z) [Gauss] }; typedef struct mip_sensor_scaled_mag_data mip_sensor_scaled_mag_data; @@ -201,6 +208,7 @@ void insert_mip_sensor_scaled_mag_data(struct mip_serializer* serializer, const void extract_mip_sensor_scaled_mag_data(struct mip_serializer* serializer, mip_sensor_scaled_mag_data* self); bool extract_mip_sensor_scaled_mag_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -219,6 +227,7 @@ void insert_mip_sensor_scaled_pressure_data(struct mip_serializer* serializer, c void extract_mip_sensor_scaled_pressure_data(struct mip_serializer* serializer, mip_sensor_scaled_pressure_data* self); bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -230,7 +239,7 @@ bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field* struct mip_sensor_delta_theta_data { - float delta_theta[3]; ///< (x, y, z) [radians] + mip_vector3f delta_theta; ///< (x, y, z) [radians] }; typedef struct mip_sensor_delta_theta_data mip_sensor_delta_theta_data; @@ -238,6 +247,7 @@ void insert_mip_sensor_delta_theta_data(struct mip_serializer* serializer, const void extract_mip_sensor_delta_theta_data(struct mip_serializer* serializer, mip_sensor_delta_theta_data* self); bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -249,7 +259,7 @@ bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field* fiel struct mip_sensor_delta_velocity_data { - float delta_velocity[3]; ///< (x, y, z) [g*sec] + mip_vector3f delta_velocity; ///< (x, y, z) [g*sec] }; typedef struct mip_sensor_delta_velocity_data mip_sensor_delta_velocity_data; @@ -257,6 +267,7 @@ void insert_mip_sensor_delta_velocity_data(struct mip_serializer* serializer, co void extract_mip_sensor_delta_velocity_data(struct mip_serializer* serializer, mip_sensor_delta_velocity_data* self); bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -277,7 +288,7 @@ bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field* f struct mip_sensor_comp_orientation_matrix_data { - float m[9]; ///< Matrix elements in row-major order. + mip_matrix3f m; ///< Matrix elements in row-major order. }; typedef struct mip_sensor_comp_orientation_matrix_data mip_sensor_comp_orientation_matrix_data; @@ -285,6 +296,7 @@ void insert_mip_sensor_comp_orientation_matrix_data(struct mip_serializer* seria void extract_mip_sensor_comp_orientation_matrix_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -295,15 +307,15 @@ bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const struct mip /// EQSTART p^{veh} = q^{-1} p^{ned} q EQEND
/// /// Where:
-/// EQSTART q = (q_w, q_x, q_y, q_z) ENDEQ is the quaternion desrcribing the rotation.
-/// EQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) ENDEQ and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
-/// EQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) ENDEQ and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
+/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
+/// EQSTART 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.
+/// EQSTART 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.
/// ///@{ struct mip_sensor_comp_quaternion_data { - float q[4]; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND + 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; @@ -311,6 +323,7 @@ void insert_mip_sensor_comp_quaternion_data(struct mip_serializer* serializer, c void extract_mip_sensor_comp_quaternion_data(struct mip_serializer* serializer, mip_sensor_comp_quaternion_data* self); bool extract_mip_sensor_comp_quaternion_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -332,6 +345,7 @@ void insert_mip_sensor_comp_euler_angles_data(struct mip_serializer* serializer, void extract_mip_sensor_comp_euler_angles_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -342,7 +356,7 @@ bool extract_mip_sensor_comp_euler_angles_data_from_field(const struct mip_field struct mip_sensor_comp_orientation_update_matrix_data { - float m[9]; + mip_matrix3f m; }; typedef struct mip_sensor_comp_orientation_update_matrix_data mip_sensor_comp_orientation_update_matrix_data; @@ -350,6 +364,7 @@ void insert_mip_sensor_comp_orientation_update_matrix_data(struct mip_serializer void extract_mip_sensor_comp_orientation_update_matrix_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -368,6 +383,7 @@ void insert_mip_sensor_orientation_raw_temp_data(struct mip_serializer* serializ void extract_mip_sensor_orientation_raw_temp_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -386,6 +402,7 @@ void insert_mip_sensor_internal_timestamp_data(struct mip_serializer* serializer void extract_mip_sensor_internal_timestamp_data(struct mip_serializer* serializer, mip_sensor_internal_timestamp_data* self); bool extract_mip_sensor_internal_timestamp_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -405,6 +422,7 @@ void insert_mip_sensor_pps_timestamp_data(struct mip_serializer* serializer, con void extract_mip_sensor_pps_timestamp_data(struct mip_serializer* serializer, mip_sensor_pps_timestamp_data* self); bool extract_mip_sensor_pps_timestamp_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -415,7 +433,7 @@ bool extract_mip_sensor_pps_timestamp_data_from_field(const struct mip_field* fi /// Upon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error. /// If synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time. /// -/// Note: this data field may be deprecrated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead. +/// Note: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead. /// ///@{ @@ -426,6 +444,7 @@ 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_TIME_INITIALIZED = 0x0004; ///< True if the time has ever been set. 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; struct mip_sensor_gps_timestamp_data { @@ -442,6 +461,7 @@ bool extract_mip_sensor_gps_timestamp_data_from_field(const struct mip_field* fi 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -466,6 +486,7 @@ void insert_mip_sensor_temperature_abs_data(struct mip_serializer* serializer, c void extract_mip_sensor_temperature_abs_data(struct mip_serializer* serializer, mip_sensor_temperature_abs_data* self); bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -482,7 +503,7 @@ bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field* struct mip_sensor_up_vector_data { - float up[3]; ///< [Gs] + mip_vector3f up; ///< [Gs] }; typedef struct mip_sensor_up_vector_data mip_sensor_up_vector_data; @@ -490,6 +511,7 @@ void insert_mip_sensor_up_vector_data(struct mip_serializer* serializer, const m void extract_mip_sensor_up_vector_data(struct mip_serializer* serializer, mip_sensor_up_vector_data* self); bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -503,7 +525,7 @@ bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field* field, struct mip_sensor_north_vector_data { - float north[3]; ///< [Gauss] + mip_vector3f north; ///< [Gauss] }; typedef struct mip_sensor_north_vector_data mip_sensor_north_vector_data; @@ -511,6 +533,7 @@ void insert_mip_sensor_north_vector_data(struct mip_serializer* serializer, cons void extract_mip_sensor_north_vector_data(struct mip_serializer* serializer, mip_sensor_north_vector_data* self); bool extract_mip_sensor_north_vector_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -530,6 +553,7 @@ 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_Y = 0x0200; ///< 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; struct mip_sensor_overrange_status_data { @@ -544,6 +568,7 @@ bool extract_mip_sensor_overrange_status_data_from_field(const struct mip_field* 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -563,6 +588,7 @@ void insert_mip_sensor_odometer_data_data(struct mip_serializer* serializer, con void extract_mip_sensor_odometer_data_data(struct mip_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_sensor.hpp b/src/mip/definitions/data_sensor.hpp index 34062130c..dde268718 100644 --- a/src/mip/definitions/data_sensor.hpp +++ b/src/mip/definitions/data_sensor.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -78,17 +79,29 @@ enum struct RawAccel { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_ACCEL_RAW; + Vector3f raw_accel; ///< Native sensor counts - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float raw_accel[3] = {0}; ///< Native sensor counts + auto as_tuple() const + { + return std::make_tuple(raw_accel[0],raw_accel[1],raw_accel[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -100,17 +113,29 @@ void extract(Serializer& serializer, RawAccel& self); struct RawGyro { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_GYRO_RAW; + Vector3f raw_gyro; ///< Native sensor counts - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float raw_gyro[3] = {0}; ///< Native sensor counts + auto as_tuple() const + { + return std::make_tuple(raw_gyro[0],raw_gyro[1],raw_gyro[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -122,17 +147,29 @@ void extract(Serializer& serializer, RawGyro& self); struct RawMag { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_MAG_RAW; + Vector3f raw_mag; ///< Native sensor counts - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float raw_mag[3] = {0}; ///< Native sensor counts + auto as_tuple() const + { + return std::make_tuple(raw_mag[0],raw_mag[1],raw_mag[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -144,17 +181,29 @@ void extract(Serializer& serializer, RawMag& self); struct RawPressure { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_PRESSURE_RAW; + float raw_pressure = 0; ///< Native sensor counts - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float raw_pressure = 0; ///< Native sensor counts + auto as_tuple() const + { + return std::make_tuple(raw_pressure); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(raw_pressure)); + } }; void insert(Serializer& serializer, const RawPressure& self); void extract(Serializer& serializer, RawPressure& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -166,17 +215,29 @@ void extract(Serializer& serializer, RawPressure& self); struct ScaledAccel { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_ACCEL_SCALED; + Vector3f scaled_accel; ///< (x, y, z)[g] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scaled_accel[3] = {0}; ///< (x, y, z)[g] + auto as_tuple() const + { + return std::make_tuple(scaled_accel[0],scaled_accel[1],scaled_accel[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -188,17 +249,29 @@ void extract(Serializer& serializer, ScaledAccel& self); struct ScaledGyro { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_GYRO_SCALED; + Vector3f scaled_gyro; ///< (x, y, z) [radians/second] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scaled_gyro[3] = {0}; ///< (x, y, z) [radians/second] + auto as_tuple() const + { + return std::make_tuple(scaled_gyro[0],scaled_gyro[1],scaled_gyro[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -210,17 +283,29 @@ void extract(Serializer& serializer, ScaledGyro& self); struct ScaledMag { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_MAG_SCALED; + Vector3f scaled_mag; ///< (x, y, z) [Gauss] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scaled_mag[3] = {0}; ///< (x, y, z) [Gauss] + auto as_tuple() const + { + return std::make_tuple(scaled_mag[0],scaled_mag[1],scaled_mag[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -231,17 +316,29 @@ void extract(Serializer& serializer, ScaledMag& self); struct ScaledPressure { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_PRESSURE_SCALED; + float scaled_pressure = 0; ///< [mBar] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float scaled_pressure = 0; ///< [mBar] + auto as_tuple() const + { + return std::make_tuple(scaled_pressure); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(scaled_pressure)); + } }; void insert(Serializer& serializer, const ScaledPressure& self); void extract(Serializer& serializer, ScaledPressure& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -253,17 +350,29 @@ void extract(Serializer& serializer, ScaledPressure& self); struct DeltaTheta { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_DELTA_THETA; + Vector3f delta_theta; ///< (x, y, z) [radians] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float delta_theta[3] = {0}; ///< (x, y, z) [radians] + auto as_tuple() const + { + return std::make_tuple(delta_theta[0],delta_theta[1],delta_theta[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -275,17 +384,29 @@ void extract(Serializer& serializer, DeltaTheta& self); struct DeltaVelocity { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_DELTA_VELOCITY; + Vector3f delta_velocity; ///< (x, y, z) [g*sec] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float delta_velocity[3] = {0}; ///< (x, y, z) [g*sec] + auto as_tuple() const + { + return std::make_tuple(delta_velocity[0],delta_velocity[1],delta_velocity[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -306,17 +427,29 @@ void extract(Serializer& serializer, DeltaVelocity& self); struct CompOrientationMatrix { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_ORIENTATION_MATRIX; + Matrix3f m; ///< Matrix elements in row-major order. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float m[9] = {0}; ///< Matrix elements in row-major order. + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -327,25 +460,37 @@ void extract(Serializer& serializer, CompOrientationMatrix& self); /// EQSTART p^{veh} = q^{-1} p^{ned} q EQEND
/// /// Where:
-/// EQSTART q = (q_w, q_x, q_y, q_z) ENDEQ is the quaternion desrcribing the rotation.
-/// EQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) ENDEQ and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
-/// EQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) ENDEQ and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
+/// EQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
+/// EQSTART 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.
+/// EQSTART 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.
/// ///@{ struct CompQuaternion { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_QUATERNION; + Quatf q; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float q[4] = {0}; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND + auto as_tuple() const + { + return std::make_tuple(q[0],q[1],q[2],q[3]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -357,19 +502,31 @@ void extract(Serializer& serializer, CompQuaternion& self); struct CompEulerAngles { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_EULER_ANGLES; - - static const bool HAS_FUNCTION_SELECTOR = false; - float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] + 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"; + + + auto as_tuple() const + { + return std::make_tuple(roll,pitch,yaw); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -380,17 +537,29 @@ void extract(Serializer& serializer, CompEulerAngles& self); struct CompOrientationUpdateMatrix { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_ORIENTATION_UPDATE_MATRIX; + Matrix3f m; - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float m[9] = {0}; + auto as_tuple() 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() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -401,17 +570,29 @@ void extract(Serializer& serializer, CompOrientationUpdateMatrix& self); struct OrientationRawTemp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TEMPERATURE_RAW; + uint16_t raw_temp[4] = {0}; - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint16_t raw_temp[4] = {0}; + auto as_tuple() const + { + return std::make_tuple(raw_temp); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(raw_temp)); + } }; void insert(Serializer& serializer, const OrientationRawTemp& self); void extract(Serializer& serializer, OrientationRawTemp& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -422,17 +603,29 @@ void extract(Serializer& serializer, OrientationRawTemp& self); struct InternalTimestamp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TIME_STAMP_INTERNAL; + uint32_t counts = 0; - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint32_t counts = 0; + auto as_tuple() const + { + return std::make_tuple(counts); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(counts)); + } }; void insert(Serializer& serializer, const InternalTimestamp& self); void extract(Serializer& serializer, InternalTimestamp& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -443,18 +636,30 @@ void extract(Serializer& serializer, InternalTimestamp& self); struct PpsTimestamp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TIME_STAMP_PPS; - - static const bool HAS_FUNCTION_SELECTOR = false; - uint32_t seconds = 0; uint32_t useconds = 0; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(seconds,useconds); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(seconds),std::ref(useconds)); + } }; void insert(Serializer& serializer, const PpsTimestamp& self); void extract(Serializer& serializer, PpsTimestamp& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -465,17 +670,12 @@ void extract(Serializer& serializer, PpsTimestamp& self); /// Upon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error. /// If synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time. /// -/// Note: this data field may be deprecrated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead. +/// Note: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead. /// ///@{ struct GpsTimestamp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TIME_STAMP_GPS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -486,6 +686,7 @@ struct GpsTimestamp TIME_INITIALIZED = 0x0004, ///< True if the time has ever been set. TOW_VALID = 0x0008, ///< True if the time of week is valid. WEEK_NUMBER_VALID = 0x0010, ///< True if the week number is valid. + ALL = 0x001F, }; uint16_t value = NONE; @@ -493,19 +694,50 @@ struct GpsTimestamp ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double tow = 0; ///< GPS Time of Week [seconds] uint16_t week_number = 0; ///< GPS Week Number since 1980 [weeks] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(tow,week_number,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -520,19 +752,31 @@ void extract(Serializer& serializer, GpsTimestamp& self); struct TemperatureAbs { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TEMPERATURE_ABS; - - static const bool HAS_FUNCTION_SELECTOR = false; - float min_temp = 0; ///< [degC] float max_temp = 0; ///< [degC] float mean_temp = 0; ///< [degC] + 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"; + + + auto as_tuple() const + { + return std::make_tuple(min_temp,max_temp,mean_temp); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -549,17 +793,29 @@ void extract(Serializer& serializer, TemperatureAbs& self); struct UpVector { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_STAB_ACCEL; + Vector3f up; ///< [Gs] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float up[3] = {0}; ///< [Gs] + auto as_tuple() const + { + return std::make_tuple(up[0],up[1],up[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -573,17 +829,29 @@ void extract(Serializer& serializer, UpVector& self); struct NorthVector { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_STAB_MAG; + Vector3f north; ///< [Gauss] - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - float north[3] = {0}; ///< [Gauss] + auto as_tuple() const + { + return std::make_tuple(north[0],north[1],north[2]); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -593,11 +861,6 @@ void extract(Serializer& serializer, NorthVector& self); struct OverrangeStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_OVERRANGE_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct Status : Bitfield { enum _enumType : uint16_t @@ -613,6 +876,7 @@ struct OverrangeStatus MAG_Y = 0x0200, ///< MAG_Z = 0x0400, ///< PRESS = 0x1000, ///< + ALL = 0x1777, }; uint16_t value = NONE; @@ -620,17 +884,58 @@ struct OverrangeStatus Status(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } Status& operator=(uint16_t val) { value = val; return *this; } - Status& operator=(int val) { value = val; return *this; } + Status& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; Status status; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(status); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(status)); + } }; void insert(Serializer& serializer, const OverrangeStatus& self); void extract(Serializer& serializer, OverrangeStatus& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -640,19 +945,31 @@ void extract(Serializer& serializer, OverrangeStatus& self); struct OdometerData { - static const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_ODOMETER; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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. + 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"; + + + auto as_tuple() const + { + return std::make_tuple(speed,uncertainty,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// diff --git a/src/mip/definitions/data_shared.h b/src/mip/definitions/data_shared.h index 8f7c4ead6..6c4a0f404 100644 --- a/src/mip/definitions/data_shared.h +++ b/src/mip/definitions/data_shared.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -74,6 +75,7 @@ void insert_mip_shared_event_source_data(struct mip_serializer* serializer, cons void extract_mip_shared_event_source_data(struct mip_serializer* serializer, mip_shared_event_source_data* self); bool extract_mip_shared_event_source_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -95,6 +97,7 @@ void insert_mip_shared_ticks_data(struct mip_serializer* serializer, const mip_s void extract_mip_shared_ticks_data(struct mip_serializer* serializer, mip_shared_ticks_data* self); bool extract_mip_shared_ticks_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -117,6 +120,7 @@ void insert_mip_shared_delta_ticks_data(struct mip_serializer* serializer, const void extract_mip_shared_delta_ticks_data(struct mip_serializer* serializer, mip_shared_delta_ticks_data* self); bool extract_mip_shared_delta_ticks_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -133,6 +137,7 @@ 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_TOW = 0x0001; ///< Whole number seconds TOW has been set 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; struct mip_shared_gps_timestamp_data { @@ -149,6 +154,7 @@ bool extract_mip_shared_gps_timestamp_data_from_field(const struct mip_field* fi 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -176,6 +182,7 @@ void insert_mip_shared_delta_time_data(struct mip_serializer* serializer, const void extract_mip_shared_delta_time_data(struct mip_serializer* serializer, mip_shared_delta_time_data* self); bool extract_mip_shared_delta_time_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -201,6 +208,7 @@ void insert_mip_shared_reference_timestamp_data(struct mip_serializer* serialize void extract_mip_shared_reference_timestamp_data(struct mip_serializer* serializer, mip_shared_reference_timestamp_data* self); bool extract_mip_shared_reference_timestamp_data_from_field(const struct mip_field* field, void* ptr); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -228,6 +236,7 @@ void insert_mip_shared_reference_time_delta_data(struct mip_serializer* serializ void extract_mip_shared_reference_time_delta_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -247,6 +256,7 @@ bool extract_mip_shared_reference_time_delta_data_from_field(const struct mip_fi 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; struct mip_shared_external_timestamp_data { @@ -262,6 +272,7 @@ bool extract_mip_shared_external_timestamp_data_from_field(const struct mip_fiel 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -285,6 +296,7 @@ void extract_mip_shared_external_timestamp_data_valid_flags(struct mip_serialize 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; struct mip_shared_external_time_delta_data { @@ -300,6 +312,7 @@ bool extract_mip_shared_external_time_delta_data_from_field(const struct mip_fie 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); + ///@} /// diff --git a/src/mip/definitions/data_shared.hpp b/src/mip/definitions/data_shared.hpp index d1a9bb377..05df1eddf 100644 --- a/src/mip/definitions/data_shared.hpp +++ b/src/mip/definitions/data_shared.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -48,7 +49,7 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -static const uint8_t MIP_DATA_DESC_SHARED_START = 0xD0; +static constexpr const uint8_t MIP_DATA_DESC_SHARED_START = 0xD0; //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -65,17 +66,29 @@ static const uint8_t MIP_DATA_DESC_SHARED_START = 0xD0; struct EventSource { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_EVENT_SOURCE; + 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). - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - 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). + auto as_tuple() const + { + return std::make_tuple(trigger_id); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(trigger_id)); + } }; void insert(Serializer& serializer, const EventSource& self); void extract(Serializer& serializer, EventSource& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -89,17 +102,29 @@ void extract(Serializer& serializer, EventSource& self); struct Ticks { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_TICKS; + uint32_t ticks = 0; ///< Ticks since powerup. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint32_t ticks = 0; ///< Ticks since powerup. + auto as_tuple() const + { + return std::make_tuple(ticks); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(ticks)); + } }; void insert(Serializer& serializer, const Ticks& self); void extract(Serializer& serializer, Ticks& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -114,17 +139,29 @@ void extract(Serializer& serializer, Ticks& self); struct DeltaTicks { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_DELTA_TICKS; + uint32_t ticks = 0; ///< Ticks since last output. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint32_t ticks = 0; ///< Ticks since last output. + auto as_tuple() const + { + return std::make_tuple(ticks); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(ticks)); + } }; void insert(Serializer& serializer, const DeltaTicks& self); void extract(Serializer& serializer, DeltaTicks& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -138,11 +175,6 @@ void extract(Serializer& serializer, DeltaTicks& self); struct GpsTimestamp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_GPS_TIME; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t @@ -151,6 +183,7 @@ struct GpsTimestamp TOW = 0x0001, ///< Whole number seconds TOW has been set WEEK_NUMBER = 0x0002, ///< Week number has been set TIME_VALID = 0x0003, ///< Both TOW and Week Number have been set + ALL = 0x0003, }; uint16_t value = NONE; @@ -158,19 +191,46 @@ struct GpsTimestamp ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; double tow = 0; ///< GPS Time of Week [seconds] uint16_t week_number = 0; ///< GPS Week Number since 1980 [weeks] ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(tow,week_number,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -190,17 +250,29 @@ void extract(Serializer& serializer, GpsTimestamp& self); struct DeltaTime { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_DELTA_TIME; + double seconds = 0; ///< Seconds since last output. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - double seconds = 0; ///< Seconds since last output. + auto as_tuple() const + { + return std::make_tuple(seconds); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(seconds)); + } }; void insert(Serializer& serializer, const DeltaTime& self); void extract(Serializer& serializer, DeltaTime& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -218,17 +290,29 @@ void extract(Serializer& serializer, DeltaTime& self); struct ReferenceTimestamp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_REFERENCE_TIME; + uint64_t nanoseconds = 0; ///< Nanoseconds since initialization. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint64_t nanoseconds = 0; ///< Nanoseconds since initialization. + auto as_tuple() const + { + return std::make_tuple(nanoseconds); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(nanoseconds)); + } }; void insert(Serializer& serializer, const ReferenceTimestamp& self); void extract(Serializer& serializer, ReferenceTimestamp& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -248,17 +332,29 @@ void extract(Serializer& serializer, ReferenceTimestamp& self); struct ReferenceTimeDelta { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_REF_TIME_DELTA; + uint64_t dt_nanos = 0; ///< Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - uint64_t dt_nanos = 0; ///< Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source. + auto as_tuple() const + { + return std::make_tuple(dt_nanos); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(dt_nanos)); + } }; void insert(Serializer& serializer, const ReferenceTimeDelta& self); void extract(Serializer& serializer, ReferenceTimeDelta& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -277,17 +373,13 @@ void extract(Serializer& serializer, ReferenceTimeDelta& self); struct ExternalTimestamp { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_EXTERNAL_TIME; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t { NONE = 0x0000, NANOSECONDS = 0x0001, ///< + ALL = 0x0001, }; uint16_t value = NONE; @@ -295,18 +387,41 @@ struct ExternalTimestamp ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; uint64_t nanoseconds = 0; ValidFlags valid_flags; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(nanoseconds,valid_flags); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(nanoseconds),std::ref(valid_flags)); + } }; void insert(Serializer& serializer, const ExternalTimestamp& self); void extract(Serializer& serializer, ExternalTimestamp& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -329,17 +444,13 @@ void extract(Serializer& serializer, ExternalTimestamp& self); struct ExternalTimeDelta { - static const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_SYS_TIME_DELTA; - - static const bool HAS_FUNCTION_SELECTOR = false; - struct ValidFlags : Bitfield { enum _enumType : uint16_t { NONE = 0x0000, DT_NANOS = 0x0001, ///< + ALL = 0x0001, }; uint16_t value = NONE; @@ -347,18 +458,41 @@ struct ExternalTimeDelta ValidFlags(int val) : value((uint16_t)val) {} operator uint16_t() const { return value; } ValidFlags& operator=(uint16_t val) { value = val; return *this; } - ValidFlags& operator=(int val) { value = val; return *this; } + ValidFlags& operator=(int val) { value = uint16_t(val); return *this; } 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; } }; 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; + 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"; + + + auto as_tuple() const + { + return std::make_tuple(dt_nanos,valid_flags); + } + + auto as_tuple() + { + 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); + ///@} /// diff --git a/src/mip/definitions/data_system.h b/src/mip/definitions/data_system.h index 5277a4d17..e55e0b8bb 100644 --- a/src/mip/definitions/data_system.h +++ b/src/mip/definitions/data_system.h @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -82,6 +83,7 @@ void insert_mip_system_built_in_test_data(struct mip_serializer* serializer, con void extract_mip_system_built_in_test_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -101,6 +103,7 @@ void insert_mip_system_time_sync_status_data(struct mip_serializer* serializer, void extract_mip_system_time_sync_status_data(struct mip_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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -137,6 +140,7 @@ void insert_mip_system_gpio_state_data(struct mip_serializer* serializer, const void extract_mip_system_gpio_state_data(struct mip_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,6 +161,7 @@ void insert_mip_system_gpio_analog_value_data(struct mip_serializer* serializer, void extract_mip_system_gpio_analog_value_data(struct mip_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/data_system.hpp b/src/mip/definitions/data_system.hpp index 405310418..17170999f 100644 --- a/src/mip/definitions/data_system.hpp +++ b/src/mip/definitions/data_system.hpp @@ -1,5 +1,6 @@ #pragma once +#include "common.h" #include "descriptors.h" #include "../mip_result.h" @@ -73,17 +74,29 @@ enum struct BuiltInTest { - static const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_BUILT_IN_TEST; + 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]. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - 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 as_tuple() const + { + return std::make_tuple(result); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(result)); + } }; void insert(Serializer& serializer, const BuiltInTest& self); void extract(Serializer& serializer, BuiltInTest& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -94,18 +107,30 @@ void extract(Serializer& serializer, BuiltInTest& self); struct TimeSyncStatus { - static const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_TIME_SYNC_STATUS; - - static const bool HAS_FUNCTION_SELECTOR = false; - 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. + 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"; + + + auto as_tuple() const + { + return std::make_tuple(time_sync,last_pps_rcvd); + } + + auto as_tuple() + { + 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); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -134,17 +159,29 @@ void extract(Serializer& serializer, TimeSyncStatus& self); struct GpioState { - static const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_GPIO_STATE; + 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. - static const bool HAS_FUNCTION_SELECTOR = false; + 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"; - 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. + auto as_tuple() const + { + return std::make_tuple(states); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(states)); + } }; void insert(Serializer& serializer, const GpioState& self); void extract(Serializer& serializer, GpioState& self); + ///@} /// //////////////////////////////////////////////////////////////////////////////// @@ -156,18 +193,30 @@ void extract(Serializer& serializer, GpioState& self); struct GpioAnalogValue { - static const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; - static const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_GPIO_ANALOG_VALUE; - - static const bool HAS_FUNCTION_SELECTOR = false; - uint8_t gpio_id = 0; ///< GPIO pin number starting with 1. float value = 0; ///< Value of the GPIO line in scaled volts. + 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"; + + + auto as_tuple() const + { + return std::make_tuple(gpio_id,value); + } + + auto as_tuple() + { + return std::make_tuple(std::ref(gpio_id),std::ref(value)); + } }; void insert(Serializer& serializer, const GpioAnalogValue& self); void extract(Serializer& serializer, GpioAnalogValue& self); + ///@} /// diff --git a/src/mip/definitions/descriptors.c b/src/mip/definitions/descriptors.c index 8b5c134e6..685a3b500 100644 --- a/src/mip/definitions/descriptors.c +++ b/src/mip/definitions/descriptors.c @@ -1,171 +1,170 @@ - -#include "descriptors.h" - -#include "../utils/serialization.h" - -#ifdef __cplusplus -namespace mip { -extern "C" { -#endif // __cplusplus - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the descriptor set is valid. -/// -///@param descriptor_set -/// -///@returns true if the descriptor set is valid. -/// -bool mip_is_valid_descriptor_set(uint8_t descriptor_set) -{ - return descriptor_set != MIP_INVALID_DESCRIPTOR_SET; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the descriptor set represents some kind of data. -/// -///@param descriptor_set -/// -///@returns true if the descriptor set represents data. -/// -bool mip_is_data_descriptor_set(uint8_t descriptor_set) -{ - return (descriptor_set >= MIP_DATA_DESCRIPTOR_SET_START) && (descriptor_set < MIP_RESERVED_DESCRIPTOR_SET_START); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the descriptor set contains commands. -/// -///@param descriptor_set -/// -///@returns true if the descriptor set contains commands. -/// -bool mip_is_cmd_descriptor_set(uint8_t descriptor_set) -{ - return (descriptor_set < MIP_DATA_DESCRIPTOR_SET_START); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the descriptor is reserved for special purposes. -/// -///@param descriptor_set -/// -///@returns true if the descriptor set is reserved. -/// -bool mip_is_reserved_descriptor_set(uint8_t descriptor_set) -{ - return (descriptor_set >= MIP_RESERVED_DESCRIPTOR_SET_START); -} - - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the field descriptor is valid. -/// -///@param field_descriptor -/// -///@returns true if the field descriptor is valid. -/// -bool mip_is_valid_field_descriptor(uint8_t field_descriptor) -{ - return field_descriptor != MIP_INVALID_FIELD_DESCRIPTOR; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the field descriptor is a command. -/// -///@param field_descriptor -/// -///@returns true if the field descriptor represents a command. -/// -bool mip_is_cmd_field_descriptor(uint8_t field_descriptor) -{ - return (field_descriptor < MIP_RESPONSE_DESCRIPTOR_START); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the field descriptor is for an ack/nack reply. -/// -///@param field_descriptor -/// -///@returns true if the field descriptor represents an ack/nack reply code. -/// -bool mip_is_reply_field_descriptor(uint8_t field_descriptor) -{ - return (field_descriptor == MIP_REPLY_DESCRIPTOR); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the field descriptor contains response data from a -/// command. -/// -/// The descriptor set is assumed to be a command set. -/// -///@param field_descriptor -/// -///@returns true if the associated field contains response data. -/// -bool mip_is_response_field_descriptor(uint8_t field_descriptor) -{ - return field_descriptor >= MIP_RESPONSE_DESCRIPTOR_START && !mip_is_reserved_cmd_field_descriptor(field_descriptor); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the field descriptor is reserved. -/// -/// The descriptor set is assumed to be a command set. -/// -///@param field_descriptor -/// -///@returns true if the associated field is neither a command nor response. -/// -bool mip_is_reserved_cmd_field_descriptor(uint8_t field_descriptor) -{ - return ((field_descriptor|MIP_RESPONSE_DESCRIPTOR_START) >= MIP_RESERVED_DESCRIPTOR_START); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the field descriptor is from the shared data set. -/// -/// The descriptor set is assumed to be a data set. -/// -///@param field_descriptor -/// -///@returns true if the associated field is from the shared data set. -/// -bool mip_is_shared_data_field_descriptor(uint8_t field_descriptor) -{ - return field_descriptor >= MIP_SHARED_DATA_FIELD_DESCRIPTOR_START; -} - - -void insert_mip_function_selector(mip_serializer* serializer, enum mip_function_selector self) -{ - insert_u8(serializer, self); -} - -void extract_mip_function_selector(mip_serializer* serializer, enum mip_function_selector* self) -{ - uint8_t tmp; - extract_u8(serializer, &tmp); - *self = (enum mip_function_selector)tmp; -} - - -void insert_mip_descriptor_rate(mip_serializer* serializer, const mip_descriptor_rate* self) -{ - insert_u8(serializer, self->descriptor); - 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); -} - - -#ifdef __cplusplus -} // namespace mip -} // extern "C" -#endif // __cplusplus + +#include "descriptors.h" + +#include "../utils/serialization.h" + +#ifdef __cplusplus +namespace mip { +extern "C" { +#endif // __cplusplus + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the descriptor set is valid. +/// +///@param descriptor_set +/// +///@returns true if the descriptor set is valid. +/// +bool mip_is_valid_descriptor_set(uint8_t descriptor_set) +{ + return descriptor_set != MIP_INVALID_DESCRIPTOR_SET; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the descriptor set represents some kind of data. +/// +///@param descriptor_set +/// +///@returns true if the descriptor set represents data. +/// +bool mip_is_data_descriptor_set(uint8_t descriptor_set) +{ + return (descriptor_set >= MIP_DATA_DESCRIPTOR_SET_START) && (descriptor_set < MIP_RESERVED_DESCRIPTOR_SET_START); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the descriptor set contains commands. +/// +///@param descriptor_set +/// +///@returns true if the descriptor set contains commands. +/// +bool mip_is_cmd_descriptor_set(uint8_t descriptor_set) +{ + return !mip_is_data_descriptor_set(descriptor_set); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the descriptor is reserved for special purposes. +/// +///@param descriptor_set +/// +///@returns true if the descriptor set is reserved. +/// +bool mip_is_reserved_descriptor_set(uint8_t descriptor_set) +{ + return (descriptor_set >= MIP_RESERVED_DESCRIPTOR_SET_START); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the descriptor set represents some kind of GNSS data. +/// +///@param descriptor_set +/// +///@returns true if the descriptor set represents GNSS data. +/// +bool mip_is_gnss_data_descriptor_set(uint8_t descriptor_set) +{ + return ((descriptor_set == 0x81) || ((descriptor_set >= 0x91) && (descriptor_set <= 0x95))); +} + + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the field descriptor is valid. +/// +///@param field_descriptor +/// +///@returns true if the field descriptor is valid. +/// +bool mip_is_valid_field_descriptor(uint8_t field_descriptor) +{ + return field_descriptor != MIP_INVALID_FIELD_DESCRIPTOR; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the field descriptor is a command. +/// +///@param field_descriptor +/// +///@returns true if the field descriptor represents a command. +/// +bool mip_is_cmd_field_descriptor(uint8_t field_descriptor) +{ + return (field_descriptor < MIP_RESPONSE_DESCRIPTOR_START); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the field descriptor is for an ack/nack reply. +/// +///@param field_descriptor +/// +///@returns true if the field descriptor represents an ack/nack reply code. +/// +bool mip_is_reply_field_descriptor(uint8_t field_descriptor) +{ + return (field_descriptor == MIP_REPLY_DESCRIPTOR); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the field descriptor contains response data from a +/// command. +/// +/// The descriptor set is assumed to be a command set. +/// +///@param field_descriptor +/// +///@returns true if the associated field contains response data. +/// +bool mip_is_response_field_descriptor(uint8_t field_descriptor) +{ + return field_descriptor >= MIP_RESPONSE_DESCRIPTOR_START && !mip_is_reserved_cmd_field_descriptor(field_descriptor); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the field descriptor is reserved. +/// +/// The descriptor set is assumed to be a command set. +/// +///@param field_descriptor +/// +///@returns true if the associated field is neither a command nor response. +/// +bool mip_is_reserved_cmd_field_descriptor(uint8_t field_descriptor) +{ + return ((field_descriptor|MIP_RESPONSE_DESCRIPTOR_START) >= MIP_RESERVED_DESCRIPTOR_START); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the field descriptor is from the shared data set. +/// +/// The descriptor set is assumed to be a data set. +/// +///@param field_descriptor +/// +///@returns true if the associated field is from the shared data set. +/// +bool mip_is_shared_data_field_descriptor(uint8_t field_descriptor) +{ + return field_descriptor >= MIP_SHARED_DATA_FIELD_DESCRIPTOR_START; +} + + +void insert_mip_function_selector(mip_serializer* serializer, enum mip_function_selector self) +{ + insert_u8(serializer, self); +} + +void extract_mip_function_selector(mip_serializer* serializer, enum mip_function_selector* self) +{ + uint8_t tmp; + extract_u8(serializer, &tmp); + *self = (enum mip_function_selector)tmp; +} + + +#ifdef __cplusplus +} // namespace mip +} // extern "C" +#endif // __cplusplus diff --git a/src/mip/definitions/descriptors.h b/src/mip/definitions/descriptors.h index 5a4c1a3a0..d2a01b23d 100644 --- a/src/mip/definitions/descriptors.h +++ b/src/mip/definitions/descriptors.h @@ -4,11 +4,13 @@ #include #include #include "../utils/serialization.h" +#include "../mip_result.h" #ifdef __cplusplus #include #include +#include namespace mip { namespace C { @@ -32,6 +34,7 @@ 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); @@ -52,14 +55,6 @@ 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); -typedef struct mip_descriptor_rate -{ - uint8_t descriptor; - uint16_t decimation; -} mip_descriptor_rate; - -void insert_mip_descriptor_rate(mip_serializer* serializer, const mip_descriptor_rate* self); -void extract_mip_descriptor_rate(mip_serializer* serializer, mip_descriptor_rate* self); #ifdef __cplusplus @@ -75,17 +70,17 @@ struct CompositeDescriptor uint8_t descriptorSet; ///< MIP descriptor set. uint8_t fieldDescriptor; ///< MIP field descriptor. - CompositeDescriptor(uint8_t descSet, uint8_t fieldDesc) : descriptorSet(descSet), fieldDescriptor(fieldDesc) {} - CompositeDescriptor(uint16_t combo) : descriptorSet(combo >> 8), fieldDescriptor(combo & 0xFF) {} + constexpr CompositeDescriptor(uint8_t descSet, uint8_t fieldDesc) : descriptorSet(descSet), fieldDescriptor(fieldDesc) {} + constexpr CompositeDescriptor(uint16_t combo) : descriptorSet(combo >> 8), fieldDescriptor(combo & 0xFF) {} CompositeDescriptor& operator=(uint16_t combo) { return *this = CompositeDescriptor(combo); } - uint16_t as_u16() const { return (uint16_t(descriptorSet) << 8) | fieldDescriptor; } + constexpr uint16_t as_u16() const { return (uint16_t(descriptorSet) << 8) | fieldDescriptor; } // operator uint16_t() const { return as_u16(); } - bool operator==(const CompositeDescriptor& other) const { return other.descriptorSet == descriptorSet && other.fieldDescriptor == fieldDescriptor; } - bool operator<(const CompositeDescriptor& other) const { return descriptorSet < other.descriptorSet || (!(descriptorSet > other.descriptorSet) && (fieldDescriptor < other.fieldDescriptor)); } + constexpr bool operator==(const CompositeDescriptor& other) const { return other.descriptorSet == descriptorSet && other.fieldDescriptor == fieldDescriptor; } + constexpr bool operator<(const CompositeDescriptor& other) const { return as_u16() < other.as_u16(); } }; @@ -107,12 +102,14 @@ enum class FunctionSelector : uint8_t RESET = C::MIP_FUNCTION_RESET, }; -using DescriptorRate = C::mip_descriptor_rate; +static constexpr uint8_t INVALID_FIELD_DESCRIPTOR = C::MIP_INVALID_FIELD_DESCRIPTOR; +static constexpr uint8_t INVALID_DESCRIPTOR_SET = C::MIP_INVALID_DESCRIPTOR_SET; inline bool isValidDescriptorSet (uint8_t descriptorSet) { return C::mip_is_valid_descriptor_set(descriptorSet); } inline bool isDataDescriptorSet (uint8_t descriptorSet) { return C::mip_is_data_descriptor_set(descriptorSet); } inline bool isCommandDescriptorSet (uint8_t descriptorSet) { return C::mip_is_cmd_descriptor_set(descriptorSet); } inline bool isReservedDescriptorSet(uint8_t descriptorSet) { return C::mip_is_reserved_descriptor_set(descriptorSet); } +inline bool isGnssDataDescriptorSet(uint8_t descriptorSet) { return C::mip_is_gnss_data_descriptor_set(descriptorSet); } inline bool isValidFieldDescriptor (uint8_t fieldDescriptor) { return C::mip_is_valid_field_descriptor(fieldDescriptor); } inline bool isCommandFieldDescriptor (uint8_t fieldDescriptor) { return C::mip_is_cmd_field_descriptor(fieldDescriptor); } @@ -122,8 +119,27 @@ inline bool isReservedFieldDescriptor(uint8_t fieldDescriptor) { return C::mip inline bool isSharedDataFieldDescriptor(uint8_t fieldDescriptor) { return C::mip_is_shared_data_field_descriptor(fieldDescriptor); } -inline void insert(Serializer& serializer, const DescriptorRate& self) { return C::insert_mip_descriptor_rate(&serializer, &self); } -inline void extract(Serializer& serializer, DescriptorRate& self) { return C::extract_mip_descriptor_rate(&serializer, &self); } +//////////////////////////////////////////////////////////////////////////////// +///@brief A CmdResult that knows the corresponding command type. +/// +///@tparam MipCmd Type of the command struct. +/// +template +struct TypedResult : public CmdResult +{ + using Cmd = MipCmd; + + // Same constructor as CmdResult. + using CmdResult::CmdResult; + + ///@brief The command descriptor. + /// + static constexpr CompositeDescriptor DESCRIPTOR = MipCmd::DESCRIPTOR; + + ///@brief Returns the composite descriptor of the command. + /// + constexpr CompositeDescriptor descriptor() const { return DESCRIPTOR; } +}; } // namespace mip diff --git a/src/mip/extras/composite_result.hpp b/src/mip/extras/composite_result.hpp new file mode 100644 index 000000000..89729a049 --- /dev/null +++ b/src/mip/extras/composite_result.hpp @@ -0,0 +1,130 @@ +#pragma once + +#include "descriptor_id.hpp" + +#include "../mip_device.hpp" +#include "../mip_result.h" +#include "../definitions/descriptors.h" + + +#include +#include + +namespace mip +{ + + //////////////////////////////////////////////////////////////////////////////// + ///@brief Represents a list of zero or more actions and their results. + /// + class CompositeResult + { + public: + struct Entry + { + CmdResult result; ///< Result of action. + DescriptorId descriptor; ///< Command or action that was executed. + + operator bool() const { return result; } + bool operator!() const { return !result; } + + 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) {} + //Entry(CmdResult r, CompositeDescriptor c) : result(r), descriptor(c) {} + }; + + public: + CompositeResult() {} + CompositeResult(bool success) : m_results{Entry{success, 0x0000}} {} + CompositeResult(CmdResult result) : m_results{result} {} + CompositeResult(CompositeDescriptor cmd, CmdResult result) : m_results{{result, cmd}} {} + CompositeResult(const Entry& result) : m_results{result} {} + + bool isEmpty() const { return m_results.empty(); } + bool notEmpty() const { return !m_results.empty(); } + size_t count() const { return m_results.size(); } + + bool allSuccessful() const { return std::all_of (m_results.begin(), m_results.end(), [](const Entry& r){ return r.result.isAck(); }); } + bool allFailed() const { return std::all_of (m_results.begin(), m_results.end(), [](const Entry& r){ return !r.result.isAck(); }); } + bool anySuccessful() const { return std::any_of (m_results.begin(), m_results.end(), [](const Entry& r){ return r.result.isAck(); }); } + bool anyFailed() const { return std::any_of (m_results.begin(), m_results.end(), [](const Entry& r){ return !r.result.isAck(); }); } + bool noneSuccessful() const { return std::none_of(m_results.begin(), m_results.end(), [](const Entry& r){ return r.result.isAck(); }); } + bool noneFailed() const { return std::none_of(m_results.begin(), m_results.end(), [](const Entry& r){ return !r.result.isAck(); }); } + + bool allMatch (CmdResult result) const { return std::all_of (m_results.begin(), m_results.end(), [result](const Entry& r){ return r.result == result; }); } + bool anyMatch (CmdResult result) const { return std::any_of (m_results.begin(), m_results.end(), [result](const Entry& r){ return r.result == result; }); } + bool noneMatch(CmdResult result) const { return std::none_of(m_results.begin(), m_results.end(), [result](const Entry& r){ return r.result == result; }); } + + operator bool() const { return noneFailed(); } + bool operator!() const { return anyFailed(); } + + CmdResult summary() const + { + if (isEmpty()) return CmdResult::STATUS_NONE; + if (count() == 1) return m_results.front().result; + if (allSuccessful()) return CmdResult::ACK_OK; + if (anyMatch(CmdResult::STATUS_TIMEDOUT)) return CmdResult::STATUS_TIMEDOUT; + else return CmdResult::STATUS_ERROR; + } + + void clear() { m_results.clear(); } + + // Append result to the list. + //void append(bool success, uint8_t id=0) { m_results.push_back({success ? CmdResult::ACK_OK : CmdResult::STATUS_ERROR, 0x0000}); } + void append(CmdResult result, CompositeDescriptor desc=0x0000) { m_results.push_back({result, desc}); } + void append(Entry result) { m_results.push_back(result); } + template + void append(CmdResult result, uint16_t index=0) { append({result, DescriptorId(MipType::DESCRIPTOR, index)}); } + + // Append multiple results. + void extend(const CompositeResult& other) { m_results.insert(m_results.end(), other.m_results.begin(), other.m_results.end()); } + + // Same as append but returns *this. + CompositeResult& operator+=(bool result) { append(result); return *this; } + CompositeResult& operator+=(CmdResult result) { append(result); return *this; } + CompositeResult& operator+=(Entry result) { append(result); return *this; } + + // Same as append but returns the result. + // Useful for code like `if( !results.appendAndCheckThis( doCommand() ) { return results; /* This specific command failed */ })` + bool appendAndCheckThisCmd(bool result, uint32_t id) { append({result, id}); return result; } + bool appendAndCheckThisCmd(CmdResult result, CompositeDescriptor desc) { append({result, desc}); return result; } + bool appendAndCheckThisCmd(Entry result) { append(result); return result; } + + // Filter results (these would be a lot easier to implement with C++20's ranges filtering stuff) + // Returns a new CompositeResult (or C++20 filter view) with only the filtered results. + // Todo: Implement these as necessary. + //auto filterByStatus(CmdResult result) const {} + //auto filterByStatusNot(CmdResult result) const {} + //auto filterSuccessful() {} + //auto filterFailed() {} + //auto filterById(CompositeDescriptor) {} + + const Entry& first() const { return m_results.front(); } + Entry& first() { return m_results.front(); } + + const Entry& last() const { return m_results.back(); } + Entry& last() { return m_results.back(); } + + CmdResult firstResult() const { return m_results.front().result; } + CmdResult lastResult() const { return m_results.back().result; } + + auto begin() { return m_results.begin(); } + auto end() { return m_results.end(); } + + auto begin() const { return m_results.begin(); } + auto end() const { return m_results.end(); } + + private: + std::vector m_results; + }; + + + template + CompositeResult::Entry runCommandEx(DeviceInterface& device, const Cmd& cmd, Args&&... args) + { + CmdResult result = device.runCommand(cmd, std::forward(args)...); + + return {result, {Cmd::DESCRIPTOR_SET, Cmd::FIELD_DESCRIPTOR}}; + } + +} // namespace mip diff --git a/src/mip/extras/descriptor_id.hpp b/src/mip/extras/descriptor_id.hpp new file mode 100644 index 000000000..768f97045 --- /dev/null +++ b/src/mip/extras/descriptor_id.hpp @@ -0,0 +1,45 @@ +#pragma once + +#include "../definitions/descriptors.h" + +#include + + +namespace mip +{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief A combination of a MIP descriptor pair and u16 ID value. +/// +/// Used by CompositeResult as a way to identify both MIP and non-MIP entries. +/// +class DescriptorId +{ +public: + DescriptorId() : m_key(0) {} + DescriptorId(uint8_t desc_set, uint8_t field_desc, uint16_t index=0) : DescriptorId({desc_set, field_desc}, index) {} + DescriptorId(CompositeDescriptor desc, uint16_t index=0) : m_key(uint32_t(desc.as_u16() << 16) | index) {} + //DescriptorId(uint16_t index) : m_key(index) {} + DescriptorId(uint32_t id) : m_key(id) {} + + bool isNull() const { return m_key == 0x00000000; } + + bool isMip() const { return descriptor().as_u16() != 0x0000; } + bool isNonMip() const { return !isMip(); } + + CompositeDescriptor descriptor() const { return m_key >> 16; } + uint16_t index() const { return m_key & 0xFFFF; } + uint32_t asU32() const { return m_key; } + + bool operator==(const DescriptorId& other) const { return m_key == other.m_key; } + bool operator!=(const DescriptorId& other) const { return m_key != other.m_key; } + bool operator<=(const DescriptorId& other) const { return m_key <= other.m_key; } + bool operator>=(const DescriptorId& other) const { return m_key >= other.m_key; } + bool operator< (const DescriptorId& other) const { return m_key < other.m_key; } + bool operator> (const DescriptorId& other) const { return m_key > other.m_key; } + +private: + uint32_t m_key; +}; + +} // namespace mip diff --git a/src/mip/extras/device_models.c b/src/mip/extras/device_models.c new file mode 100644 index 000000000..8566c0958 --- /dev/null +++ b/src/mip/extras/device_models.c @@ -0,0 +1,96 @@ + +#include "device_models.h" + +#include +#include +#include +#include + +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { +#endif// __cplusplus + +mip_model_number get_model_from_string(const char* model_or_serial) +{ + unsigned int start_index = 0; + + // The model number is just the portion of the serial or model string before the dot or dash + // serial and model number fields are 16 chars + unsigned int i = 0; + for (; model_or_serial[i] != '\0'; i++) + { + // Unsigned is important. Passing a negative value to isdigit or + // isspace is undefined behavior and can trigger assertions. + const unsigned char c = model_or_serial[i]; + + if (!isdigit(c)) + { + if (c == '.' || c == '-') + break; + + if (isspace(c) && (start_index == i)) + start_index++; + else + return MODEL_UNKNOWN; + } + } + + // Must get at least 4 digits. + if (i < start_index + 4) + return MODEL_UNKNOWN; + + return atoi(model_or_serial + start_index); +} + +const char* get_model_name_from_number(mip_model_number model) +{ + switch (model) + { + case MODEL_3DM_DH3: return "3DM-DH3"; + case MODEL_3DM_GX3_15: return "3DM-GX3-15"; + case MODEL_3DM_GX3_25: return "3DM-GX3-25"; + case MODEL_3DM_GX3_35: return "3DM-GX3-35"; + case MODEL_3DM_GX3_45: return "3DM-GX3-45"; + case MODEL_3DM_RQ1_45_LT: return "3DM-RQ1-45_LT"; + case MODEL_3DM_GX4_15: return "3DM-GX4-15"; + case MODEL_3DM_GX4_25: return "3DM-GX4-25"; + case MODEL_3DM_GX4_45: return "3DM-GX4-45"; + case MODEL_3DM_RQ1_45_ST: return "3DM-RQ1-45_ST"; + case MODEL_3DM_GX5_10: return "3DM-GX5-10"; + case MODEL_3DM_GX5_15: return "3DM-GX5-15"; + case MODEL_3DM_GX5_25: return "3DM-GX5-25"; + case MODEL_3DM_GX5_35: return "3DM-GX5-35"; + case MODEL_3DM_GX5_45: return "3DM-GX5-45"; + case MODEL_3DM_CV5_10: return "3DM-CV5-10"; + case MODEL_3DM_CV5_15: return "3DM-CV5-15"; + case MODEL_3DM_CV5_25: return "3DM-CV5-25"; + case MODEL_3DM_CV5_45: return "3DM-CV5-45"; + case MODEL_3DM_GQ4_45: return "3DM-GQ4-45"; + case MODEL_3DM_CX5_45: return "3DM-CX5-45"; + case MODEL_3DM_CX5_35: return "3DM-CX5-35"; + 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_15: return "3DM-CL5-15"; + case MODEL_3DM_CL5_25: return "3DM-CL5-25"; + case MODEL_3DM_GQ7: return "3DM-GQ7"; + case MODEL_3DM_RTK: return "3DM-RTK"; + case MODEL_3DM_CV7_AHRS: return "3DM-CV7-AHRS"; + case MODEL_3DM_CV7_AR: return "3DM-CV7-AR"; + case MODEL_3DM_GV7_AHRS: return "3DM-GV7-AHRS"; + case MODEL_3DM_GV7_AR: return "3DM-GV7-AR"; + case MODEL_3DM_GV7_INS: return "3DM-GV7-INS"; + case MODEL_3DM_CV7_INS: return "3DM-CV7-INS"; + + default: + case MODEL_UNKNOWN: return ""; + } +} + +#ifdef __cplusplus +} // extern "C" +} // namespace C +} // namespace mip +#endif // __cplusplus diff --git a/src/mip/extras/device_models.h b/src/mip/extras/device_models.h new file mode 100644 index 000000000..5b47ce67b --- /dev/null +++ b/src/mip/extras/device_models.h @@ -0,0 +1,69 @@ +#pragma once + +#ifdef __cplusplus +namespace mip { +namespace C +{ +extern "C" { +#endif // __cplusplus + +enum mip_model_number +{ + MODEL_UNKNOWN = 0, + MODEL_3DM_DH3 = 6219,// 3DM-DH3 + MODEL_3DM_GX3_15 = 6227,// 3DM-GX3-15 + MODEL_3DM_GX3_25 = 6223,// 3DM-GX3-25 + MODEL_3DM_GX3_35 = 6225,// 3DM-GX3-35 + MODEL_3DM_GX3_45 = 6228,// 3DM-GX3-45 + MODEL_3DM_RQ1_45_LT = 6232,// 3DM-RQ1-45-LT + MODEL_3DM_GX4_15 = 6233,// 3DM-GX4-15 + MODEL_3DM_GX4_25 = 6234,// 3DM-GX4-25 + MODEL_3DM_GX4_45 = 6236,// 3DM-GX4-45 + MODEL_3DM_RQ1_45_ST = 6239,// 3DM-RQ1-45-ST + MODEL_3DM_GX5_10 = 6255,// 3DM-GX5-10 + MODEL_3DM_GX5_15 = 6254,// 3DM-GX5-15 + MODEL_3DM_GX5_25 = 6253,// 3DM-GX5-25 + MODEL_3DM_GX5_35 = 6252,// 3DM-GX5-35 + MODEL_3DM_GX5_45 = 6251,// 3DM-GX5-45 + MODEL_3DM_CV5_10 = 6259,// 3DM-CV5-10 + MODEL_3DM_CV5_15 = 6258,// 3DM-CV5-15 + MODEL_3DM_CV5_25 = 6257,// 3DM-CV5-25 + MODEL_3DM_CV5_45 = 6256,// 3DM-CV5-45 + MODEL_3DM_GQ4_45 = 6250,// 3DM-GQ4-45 + MODEL_3DM_CX5_45 = 6271,// 3DM-CX5-45 + MODEL_3DM_CX5_35 = 6272,// 3DM-CX5-35 + MODEL_3DM_CX5_25 = 6273,// 3DM-CX5-25 + MODEL_3DM_CX5_15 = 6274,// 3DM-CX5-15 + MODEL_3DM_CX5_10 = 6275,// 3DM-CX5-10 + MODEL_3DM_CL5_10 = 6279,// 3DM-CL5-10 + MODEL_3DM_CL5_15 = 6280,// 3DM-CL5-15 + MODEL_3DM_CL5_25 = 6281,// 3DM-CL5-25 + MODEL_3DM_GQ7 = 6284,// 3DM-GQ7 + MODEL_3DM_RTK = 6285,// 3DM-RTK + MODEL_3DM_CV7_AHRS = 6286,// 3DM-CV7-AHRS + MODEL_3DM_CV7_AR = 6287,// 3DM-CV7-AR + MODEL_3DM_GV7_AHRS = 6288,// 3DM-GV7-AHRS + MODEL_3DM_GV7_AR = 6289,// 3DM-GV7-AR + MODEL_3DM_GV7_INS = 6290,// 3DM-GV7-INS + MODEL_3DM_CV7_INS = 6291 // 3DM-CV7-INS +}; +#ifndef __cplusplus +typedef enum mip_model_number mip_model_number; +#endif // __cplusplus + +mip_model_number get_model_from_string(const char* model_or_serial); +const char* get_model_name_from_number(mip_model_number model); + + +#ifdef __cplusplus +} // extern "C" +} // namespace C + +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); } + + +} // namespace mip +#endif // __cplusplus diff --git a/src/mip/extras/index.hpp b/src/mip/extras/index.hpp new file mode 100644 index 000000000..3f31deb79 --- /dev/null +++ b/src/mip/extras/index.hpp @@ -0,0 +1,116 @@ +#pragma once + +#include +#include + +namespace mip +{ + class Id; + + //////////////////////////////////////////////////////////////////////////////// + ///@brief Represents an index ranging from 0..N excluding N. + /// + /// 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 + /// 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. + /// + /// The default value with no initialization is INVALID. + /// + /// This is interchangeable with the Id class below. + /// + class Index + { + private: + unsigned int INVALID = -1; + + public: + constexpr explicit Index(unsigned int index) : m_index(index) {} + constexpr Index() : m_index(INVALID) {} + + constexpr Index& setFromIndex(unsigned int index) { m_index = index; return *this; } + constexpr Index& setFromId(unsigned int id) { m_index = id-1; return *this; } + + constexpr unsigned int index() const { return m_index; } + constexpr unsigned int id() const { return m_index+1; } + + constexpr bool operator==(const Index& other) const { return m_index == other.m_index; } + constexpr bool operator!=(const Index& other) const { return m_index != other.m_index; } + + constexpr bool isAssigned() const { return m_index != INVALID; } + constexpr bool isValid(size_t max_count) const { return m_index < max_count; } + + constexpr void clear() { m_index = INVALID; } + + Index& operator++() { m_index++; return *this; } + Index& operator--() { m_index--; return *this; } + Index operator++(int) { Index tmp(*this); m_index++; return tmp; } + Index operator--(int) { Index tmp(*this); m_index--; return tmp; } + + constexpr Index(const Id& other); + constexpr Index& operator=(const Id& other); + + private: + unsigned int m_index; + }; + + //////////////////////////////////////////////////////////////////////////////// + ///@brief Representes an ID number ranging from 1..N including N. + /// + /// This is interchangeable with the Index class above. + /// + class Id + { + private: + unsigned int INVALID = 0; + + public: + constexpr explicit Id(unsigned int id) : m_id(id) {} + constexpr Id() : m_id(INVALID) {} + + constexpr Id& setFromIndex(unsigned int index) { m_id = index+1; return *this; } + constexpr Id& setFromId(unsigned int id) { m_id = id; return *this; } + + constexpr unsigned int index() const { return m_id-1; } + constexpr unsigned int id() const { return m_id; } + + constexpr bool operator==(const Id& other) const { return m_id == other.m_id; } + constexpr bool operator!=(const Id& other) const { return m_id != other.m_id; } + + constexpr bool isAssigned() const { return m_id != INVALID; } + constexpr bool isValid(size_t max_count) const { return index() < max_count; } + + constexpr void clear() { m_id = INVALID; } + + Id& operator++() { m_id++; return *this; } + Id& operator--() { m_id--; return *this; } + Id operator++(int) { Id tmp(*this); m_id++; return tmp; } + Id operator--(int) { Id tmp(*this); m_id--; return tmp; } + + constexpr Id(const Index& other) : m_id(other.id()) {} + constexpr Id& operator=(const Index& other) { return setFromIndex(other.index()); } + + private: + unsigned int m_id; + }; + + inline constexpr Index::Index(const Id& other) : m_index(other.index()) {} + inline constexpr Index& Index::operator=(const Id& other) { return setFromIndex(other.index()); } + + inline constexpr bool operator==(Id l, Index r) { return l.index() == r.index(); } + inline constexpr bool operator==(Index l, Id r) { return l.index() == r.index(); } + + // Get a pointer to a value in the container at index, or NULL if index out of range. + template + auto* indexOrNull(Container& container, Index index) { return index.isValid(container.size()) ? &container[index.index()] : nullptr; } + + // Get the value in the container at index, or a default value if index out of range. + template + auto indexOrDefault(Container& container, Index index, Value default_) { return index.isValid(container.size()) ? container[index.index()] : default_; } + +} // namespace mip diff --git a/src/mip/extras/recording_connection.cpp b/src/mip/extras/recording_connection.cpp new file mode 100644 index 000000000..b9a3e7d7a --- /dev/null +++ b/src/mip/extras/recording_connection.cpp @@ -0,0 +1,48 @@ +#include "recording_connection.hpp" + +namespace mip +{ +namespace extras +{ + +///@brief Creates a RecordingConnection that will write received bytes to recvStream, and sent bytes to sendStream +/// +///@param connection Connection object that will actually communicate with the device +///@param recvStream The stream to write to when bytes are received. Null if received bytes should not be written to a stream +///@param sendStream The stream to write to when bytes are sent. Null if sent bytes should not be written to a stream +RecordingConnection::RecordingConnection(Connection* connection, std::ostream* recvStream, std::ostream* sendStream) : + mConnection(connection), mRecvFile(recvStream), mSendFile(sendStream) +{ + mType = TYPE; +} + +///@copydoc mip::Connection::sendToDevice +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); + + mSendFileWritten += length; + } + + return ok; +} + +///@copydoc mip::Connection::recvFromDevice +bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, 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); + + mRecvFileWritten += *count_out; + } + + return ok; +} + +} // namespace extras +} // namespace mip \ No newline at end of file diff --git a/src/mip/extras/recording_connection.hpp b/src/mip/extras/recording_connection.hpp new file mode 100644 index 000000000..4297d7651 --- /dev/null +++ b/src/mip/extras/recording_connection.hpp @@ -0,0 +1,101 @@ +#pragma once + +#include + +#include +#include +#include + +namespace mip +{ +namespace extras +{ + +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_extras Extra utilities +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief Can be used with another connection to communicate with a device, and record the data at the same time +/// +class RecordingConnection : public Connection +{ +public: + static constexpr auto TYPE = "Recording"; + + RecordingConnection(Connection *connection, std::ostream *recvStream = nullptr, std::ostream *sendStream = nullptr); + + 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 isConnected() const + { + if(mConnection) + return mConnection->isConnected(); + + return false; + }; + + bool connect() + { + if (mConnection) return mConnection->connect(); + + return false; + }; + bool disconnect() + { + if (mConnection) return mConnection->disconnect(); + + return false; + }; + + const char* interfaceName() const override { return mConnection->interfaceName(); } + uint32_t parameter() const override { return mConnection->parameter(); } + + uint64_t recvFileBytesWritten() + { + return mRecvFileWritten; + } + + uint64_t sendFileBytesWritten() + { + return mSendFileWritten; + } + +protected: + Connection* mConnection; + + // Files may be NULL to not record one direction or the other + std::ostream* mRecvFile; + std::ostream* mSendFile; + + uint64_t mRecvFileWritten = 0; + uint64_t mSendFileWritten = 0; +}; + +//////////////////////////////////////////////////////////////////////////////// +///@brief Template wrapper for a recording connection. +/// +///@param ConnectionType The type of connection used to actually communicate. +/// +template +class RecordingConnectionWrapper : public RecordingConnection +{ +public: + ///@brief Creates a RecordingConnectionWrapper that will write received bytes to recvStream, sent bytes to sendStream, and construct a connection object from args + /// + ///@param recvStream The stream to write to when bytes are received. Null if received bytes should not be written to a stream + ///@param sendStream The stream to write to when bytes are sent. Null if sent bytes should not be written to a stream + ///@param args Arguments required to construct the ConnectionType + template + RecordingConnectionWrapper(std::ostream* recvStream, std::ostream* sendStream, Args&&... args) : RecordingConnection(new ConnectionType(std::forward(args)...), recvStream, sendStream) {} + + ///@brief Deconstructs the RecordingConnectionWrapper as well as the underlying connection object made in the constructor + ~RecordingConnectionWrapper() { delete mConnection; } +}; + +///@} +//////////////////////////////////////////////////////////////////////////////// + +} // namespace extras +} // namespace mip diff --git a/src/mip/extras/scope_helper.cpp b/src/mip/extras/scope_helper.cpp new file mode 100644 index 000000000..75c574262 --- /dev/null +++ b/src/mip/extras/scope_helper.cpp @@ -0,0 +1,26 @@ +#include "scope_helper.hpp" + +namespace mip +{ + namespace extras + { + ScopeHelper::ScopeHelper(std::function scopeFunction) : + m_outOfScopeFunction(scopeFunction), + m_canceled(false) + { + } + + ScopeHelper::~ScopeHelper() + { + if (!m_canceled) + { + m_outOfScopeFunction(); + } + } + + void ScopeHelper::cancel() + { + m_canceled = true; + } + } //namespace extras +} //namespace mip \ No newline at end of file diff --git a/src/mip/extras/scope_helper.hpp b/src/mip/extras/scope_helper.hpp new file mode 100644 index 000000000..ab2386a8d --- /dev/null +++ b/src/mip/extras/scope_helper.hpp @@ -0,0 +1,45 @@ +#pragma once + +#include +#include + +namespace mip +{ + 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 diff --git a/src/mip/extras/version.cpp b/src/mip/extras/version.cpp new file mode 100644 index 000000000..d5b63c57c --- /dev/null +++ b/src/mip/extras/version.cpp @@ -0,0 +1,74 @@ + +#include "version.hpp" + +#include + + +namespace mip +{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief Convert the version to a string in the standard X.Y.ZZ format. +/// +/// Note: The result is unspecified for invalid version numbers. +/// +///@param buffer Character buffer to write into. +///@param buffer_size Length (including space for null terminator) of buffer. +/// +void FirmwareVersion::toString(char* buffer, size_t buffer_size) const +{ + std::snprintf(buffer, buffer_size, "%u.%u.%02u", major(), minor(), patch()); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a standard-format string (X.Y.ZZ\0 or XYZZ\0). +/// +///@param str Input string. Can be unterminated if length is specified. +///@param length Length of input string. Assumed to be NULL-terminated if -1. +/// +///@return True if a valid version was parsed. +/// +bool FirmwareVersion::fromString(const char* str, size_t length) +{ + m_version = 0; + + unsigned int digit = 0; + for(unsigned int i=0; i= 4) + break; + } + + return isValid(); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Convert a FirmwareVersion to a string separated by periods. +/// +/// This is different from Version::toString in that the patch number uses +/// zero-padding. +/// +std::string FirmwareVersion::toString() const +{ + char buffer[3+1+3+1+3+1]; + + toString(buffer, sizeof(buffer)); + + return buffer; +} + +} // namespace mip diff --git a/src/mip/extras/version.hpp b/src/mip/extras/version.hpp new file mode 100644 index 000000000..3ff7a6628 --- /dev/null +++ b/src/mip/extras/version.hpp @@ -0,0 +1,70 @@ +#pragma once + +#include +#include + +#include + +#if __cpp_lib_string_view >= 201606L +#include +#endif + +namespace mip +{ + +//////////////////////////////////////////////////////////////////////////// +///@brief Represents the device firmware version. +/// +/// Device firmware is of the form X.Y.ZZ, where: +/// - X is the major version, exactly 1 digit. +/// - Y is the minor version, exactly 1 digit. +/// - Z is the patch version, exactly 2 digits. +/// +/// Internally this class stores the version as a 16-bit unsigned integer. +/// +class FirmwareVersion +{ +public: + FirmwareVersion() = default; + FirmwareVersion(uint8_t major, uint8_t minor, uint8_t patch) { fromParts(major, minor, patch); } + explicit FirmwareVersion(uint16_t version) : m_version(version) {} + + FirmwareVersion(const FirmwareVersion&) = default; + FirmwareVersion& operator=(const FirmwareVersion&) = default; + FirmwareVersion& operator=(uint16_t version) { m_version = version; return *this; } + + bool isNull() const { return m_version == 0; } + bool isValid() const { return !isNull() && major() < 10 && minor() < 10 && patch() < 100; } + bool isDevVersion() const { return major() == 0; } + bool isReleaseVersion() const { return major() > 0; } + bool isSpecialVersion() const { return major() > 1; } + + uint16_t asU16() const { return m_version; } + uint16_t& asU16() { return m_version; } + + void fromParts(uint8_t major, uint8_t minor, uint8_t patch) { m_version = major * 1000 + minor * 100 + patch; } + + uint8_t major() const { return uint8_t(m_version / 1000); } + uint8_t minor() const { return (m_version / 100) % 10; } + uint8_t patch() const { return m_version % 100; } + + bool operator==(FirmwareVersion other) const { return m_version == other.m_version; } + bool operator!=(FirmwareVersion other) const { return m_version != other.m_version; } + bool operator<=(FirmwareVersion other) const { return m_version <= other.m_version; } + bool operator>=(FirmwareVersion other) const { return m_version >= other.m_version; } + bool operator< (FirmwareVersion other) const { return m_version < other.m_version; } + bool operator> (FirmwareVersion other) const { return m_version > other.m_version; } + + void toString(char* buffer, size_t buffer_size) const; + bool fromString(const char* str, size_t length=-1); + + std::string toString() const; +#if __cpp_lib_string_view >= 201606L + bool fromString(std::string_view str) { return fromString(str.data(), str.size()); } +#endif + +private: + uint16_t m_version = 0; +}; + +} // namespace mip diff --git a/src/mip/mip.hpp b/src/mip/mip.hpp index 4c4832e63..637fe2168 100644 --- a/src/mip/mip.hpp +++ b/src/mip/mip.hpp @@ -1,326 +1,506 @@ -#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 - -//////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_cpp MIP 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. -/// -///@see mip_cpp -/// -namespace mip -{ - -using PacketLength = C::packet_length; - -template struct MipFieldInfo; - -//////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_cpp -///@{ - -//////////////////////////////////////////////////////////////////////////////// -///@brief C++ class representing a MIP field. -/// -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)); } - - ///@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); } - ///@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); } - - template - bool extract(Field& field) const { return mip::extract(field, payload(), payloadLength(), 0, true); } - - ///@brief Index the payload at the given location. - ///@param index - ///@returns payload byte - uint8_t payload(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); } - - - ///@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 contains a data field. - bool isData() const { return isDataDescriptorSet(descriptorSet()); } - - ///@brief Determines if the field holds a command. - bool isCommand() const { return isCommandSet() && isCommandFieldDescriptor(fieldDescriptor()); } - - ///@brief Determines if the field holds command response data. - bool isResponse() const { return isCommandSet() && isResponseFieldDescriptor(fieldDescriptor()); } - - ///@brief Determines if the field holds an ack/nack reply code. - bool isReply() const { return isCommandSet() && isReplyFieldDescriptor(fieldDescriptor()) && payloadLength()==2; } -}; - - -//////////////////////////////////////////////////////////////////////////////// -///@brief C++ class representing a MIP Packet. -/// -/// Fields may be iterated over using the C-style method or with a range-based -/// for loop: -///@code{.cpp} -/// for(Field field : packet) { ... } -///@endcode -/// -class Packet : public C::mip_packet -{ - class FieldIterator; - -public: - ///@copydoc mip::C::mip_packet_create - Packet(uint8_t* buffer, size_t bufferSize, uint8_t descriptorSet) { C::mip_packet_create(this, buffer, bufferSize, descriptorSet); } - ///@copydoc mip_packet_from_buffer - Packet(uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, buffer, length); } - /// Constructs a C++ %Packet class from the base C object. - Packet(const C::mip_packet* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } - /// Constructs a C++ %Packet class from the base C object. - Packet(const C::mip_packet& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } - - uint8_t descriptorSet() const { return C::mip_packet_descriptor_set(this); } ///<@copydoc mip::C::mip_packet_descriptor_set - PacketLength 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); } - bool isCommand() 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 - - PacketLength bufferSize() const { return C::mip_packet_buffer_size(this); } ///<@copydoc mip::C::mip_packet_buffer_size - RemainingCount 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, size_t payloadLength) { return C::mip_packet_add_field(this, fieldDescriptor, payload, payloadLength); } ///<@copydoc mip::C::mip_packet_add_field - RemainingCount 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 - RemainingCount 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 - RemainingCount 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. - - /// Returns the first field in the packet. - Field firstField() const { return Field(C::mip_field_first_from_packet(this)); } - - /// Returns a forward iterator to the first field in the packet. - ///@internal - FieldIterator begin() const { return firstField(); } - - /// Returns a sentry object representing the end of fields in the packet. - ///@internal -#if __cpp_range_based_for >= 201603 - std::nullptr_t end() const { return nullptr; } -#else - FieldIterator end() const { return Field(); } -#endif - - template - bool addField(const Field& field, uint8_t fieldDescriptor = Field::FIELD_DESCRIPTOR) - { - uint8_t* payload; - size_t available = allocField(fieldDescriptor, 0, &payload); - Serializer serializer(payload, available); - insert(serializer, field); - return reallocLastField(payload, serializer.length()) >= 0; - } - - template - static Packet createFromField(uint8_t* buffer, size_t bufferSize, const Field& field, uint8_t fieldDescriptor=Field::FIELD_DESCRIPTOR) - { - Packet packet(buffer, bufferSize, Field::DESCRIPTOR_SET); - packet.addField(field, fieldDescriptor); - packet.finalize(); - return packet; - } - -private: - /// Iterator class for use with the range-based for loop. - ///@internal - class FieldIterator - { - public: - FieldIterator(const Field& first) : mField(first) {} - FieldIterator() {} - - 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); } - - bool operator==(std::nullptr_t) const { return !mField.isValid(); } - bool operator!=(std::nullptr_t) const { return mField.isValid(); } - - const Field& operator*() const { return mField; } - - FieldIterator& operator++() { mField.next(); return *this; } - private: - Field mField; - }; - -}; - - -//////////////////////////////////////////////////////////////////////////////// -///@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 Packet*,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 - RemainingCount parse(const uint8_t* inputBuffer, size_t inputCount, Timestamp timestamp, unsigned int maxPackets) { 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 Packet& 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)(Packet(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 +#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 + +//////////////////////////////////////////////////////////////////////////////// +///@defgroup mip_cpp MIP 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. +/// +///@see mip_cpp +/// +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 + 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 + + 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; + Serializer serializer(*this, fieldDescriptor); + insert(serializer, field); + C::mip_serializer_finish_new_field(&serializer, this); + return serializer.isOk(); + } + + ///@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 5b14d8c26..f07cf6852 100644 --- a/src/mip/mip_all.h +++ b/src/mip/mip_all.h @@ -27,4 +27,3 @@ #include "definitions/data_sensor.h" #include "definitions/data_gnss.h" #include "definitions/data_filter.h" - diff --git a/src/mip/mip_all.hpp b/src/mip/mip_all.hpp index 5dc37a50d..da6d5476b 100644 --- a/src/mip/mip_all.hpp +++ b/src/mip/mip_all.hpp @@ -20,6 +20,7 @@ #include "definitions/commands_gnss.hpp" #include "definitions/commands_rtk.hpp" #include "definitions/commands_system.hpp" +#include "definitions/commands_aiding.hpp" //MIP Data #include "definitions/data_shared.hpp" @@ -31,5 +32,3 @@ //MIP Helpers #include "mip.hpp" #include "mip_device.hpp" - - diff --git a/src/mip/mip_cmdqueue.c b/src/mip/mip_cmdqueue.c index dbb6cdc5e..24874891d 100644 --- a/src/mip/mip_cmdqueue.c +++ b/src/mip/mip_cmdqueue.c @@ -39,7 +39,7 @@ void mip_pending_cmd_init(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t ///@param additional_time /// Additional time on top of the base reply timeout for this specific command. /// -void mip_pending_cmd_init_with_timeout(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, timeout_type additional_time) +void mip_pending_cmd_init_with_timeout(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, mip_timeout additional_time) { mip_pending_cmd_init_full(cmd, descriptor_set, field_descriptor, 0x00, NULL, 0, additional_time); } @@ -57,8 +57,6 @@ void mip_pending_cmd_init_with_timeout(mip_pending_cmd* cmd, uint8_t descriptor_ ///@param response_buffer /// Optional buffer to hold response data, if any. If NULL, response_buffer_size must be 0. ///@param response_buffer_size -/// Optional buffer to hold response data, if any. If NULL, response_buffer_size must be 0. -///@param response_buffer_size /// Size of the response buffer. The response will be limited to this size. /// void mip_pending_cmd_init_with_response(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, uint8_t response_descriptor, uint8_t* response_buffer, uint8_t response_buffer_size) @@ -83,7 +81,7 @@ void mip_pending_cmd_init_with_response(mip_pending_cmd* cmd, uint8_t descriptor ///@param additional_time /// Additional time on top of the base reply timeout for this specific command. /// -void mip_pending_cmd_init_full(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, uint8_t response_descriptor, uint8_t* response_buffer, uint8_t response_buffer_size, timeout_type additional_time) +void mip_pending_cmd_init_full(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, uint8_t response_descriptor, uint8_t* response_buffer, uint8_t response_buffer_size, mip_timeout additional_time) { cmd->_next = NULL; cmd->_response_buffer = NULL; @@ -108,6 +106,14 @@ enum mip_cmd_result mip_pending_cmd_status(const mip_pending_cmd* cmd) return cmd->_status; } +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the response descriptor. +/// +uint8_t mip_pending_cmd_response_descriptor(const mip_pending_cmd* cmd) +{ + return cmd->_response_descriptor; +} + //////////////////////////////////////////////////////////////////////////////// ///@brief Returns the response payload pointer. /// @@ -134,6 +140,29 @@ uint8_t mip_pending_cmd_response_length(const mip_pending_cmd* cmd) return cmd->_response_length; } +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines how much time is remaining before the command times out. +/// +/// For most cases you should instead call mip_pending_cmd_check_timeout() to +/// know if the command has timed out or not. +/// +///@param cmd The command to check. Must be in MIP_STATUS_WAITING state. +///@param now The current timestamp. +/// +///@warning The command must be in the MIP_STATUS_WAITING state, otherwise the +/// result is unspecified. +/// +///@returns The time remaining before the command times out. The value will be +/// negative if the timeout time has passed. +/// +int mip_pending_cmd_remaining_time(const mip_pending_cmd* cmd, mip_timestamp now) +{ + assert(cmd->_status == MIP_STATUS_WAITING); + + // result <= 0 if timed out. + // Note: this still works with unsigned overflow. + return (int)(now - cmd->_timeout_time); +} //////////////////////////////////////////////////////////////////////////////// ///@brief Checks if the command should time out. @@ -144,11 +173,11 @@ uint8_t mip_pending_cmd_response_length(const mip_pending_cmd* cmd) ///@returns true if the command should time out. Only possible for MIP_STATUS_WAITING. ///@returns false if the command should not time out. /// -bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, timestamp_type now) +bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, mip_timestamp now) { if( cmd->_status == MIP_STATUS_WAITING ) { - if( (int)(now - cmd->_timeout_time) > 0 ) + if( mip_pending_cmd_remaining_time(cmd, now) > 0 ) { return true; } @@ -168,10 +197,16 @@ bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, timestamp_type no /// used to accommodate long communication latencies, such as when using /// a TCP connection. /// -void mip_cmd_queue_init(mip_cmd_queue* queue, timeout_type base_reply_timeout) +void mip_cmd_queue_init(mip_cmd_queue* queue, mip_timeout base_reply_timeout) { queue->_first_pending_cmd = NULL; queue->_base_timeout = base_reply_timeout; + + MIP_DIAG_ZERO(queue->_diag_cmds_queued); + MIP_DIAG_ZERO(queue->_diag_cmds_acked); + MIP_DIAG_ZERO(queue->_diag_cmds_nacked); + MIP_DIAG_ZERO(queue->_diag_cmds_timedout); + MIP_DIAG_ZERO(queue->_diag_cmds_failed); } //////////////////////////////////////////////////////////////////////////////// @@ -192,6 +227,8 @@ void mip_cmd_queue_enqueue(mip_cmd_queue* queue, mip_pending_cmd* cmd) return; } + MIP_DIAG_INC(queue->_diag_cmds_queued, 1); + cmd->_status = MIP_STATUS_PENDING; queue->_first_pending_cmd = cmd; } @@ -228,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, timeout_type base_timeout, timestamp_type timestamp) +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) { 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. @@ -335,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, timestamp_type timestamp) +void mip_cmd_queue_process_packet(mip_cmd_queue* queue, const mip_packet* packet, mip_timestamp timestamp) { // Check if the packet is a command descriptor set. const uint8_t descriptor_set = mip_packet_descriptor_set(packet); @@ -355,6 +392,17 @@ void mip_cmd_queue_process_packet(mip_cmd_queue* queue, const mip_packet* packet // This must be done last b/c it may trigger the thread which queued the command. // The command could go out of scope or its attributes inspected. pending->_status = status; + +#ifdef MIP_ENABLE_DIAGNOSTICS + if( mip_cmd_result_is_ack(status) ) + MIP_DIAG_INC(queue->_diag_cmds_acked, 1); + else if( mip_cmd_result_is_reply(status) ) + MIP_DIAG_INC(queue->_diag_cmds_nacked, 1); + else if( status == MIP_STATUS_TIMEDOUT ) + MIP_DIAG_INC(queue->_diag_cmds_timedout, 1); + else + MIP_DIAG_INC(queue->_diag_cmds_failed, 1); +#endif // MIP_ENABLE_DIAGNOSTICS } } } @@ -374,7 +422,7 @@ void mip_cmd_queue_clear(mip_cmd_queue* queue) queue->_first_pending_cmd = pending->_next; // This may deallocate the pending command in another thread (make sure to fetch the next cmd first). - pending->_status = MIP_STATUS_ERROR; + pending->_status = MIP_STATUS_CANCELLED; } } @@ -389,7 +437,7 @@ void mip_cmd_queue_clear(mip_cmd_queue* queue) ///@param queue ///@param now /// -void mip_cmd_queue_update(mip_cmd_queue* queue, timestamp_type now) +void mip_cmd_queue_update(mip_cmd_queue* queue, mip_timestamp now) { if( queue->_first_pending_cmd ) { @@ -411,6 +459,8 @@ void mip_cmd_queue_update(mip_cmd_queue* queue, timestamp_type now) // This must be last! pending->_status = MIP_STATUS_TIMEDOUT; + + MIP_DIAG_INC(queue->_diag_cmds_timedout, 1); } } } @@ -418,12 +468,13 @@ void mip_cmd_queue_update(mip_cmd_queue* queue, timestamp_type now) //////////////////////////////////////////////////////////////////////////////// ///@brief Sets the base reply timeout for all commands. /// -/// THe base reply timeout is the minimum time to wait for a reply. +/// The base reply timeout is the minimum time to wait for a reply. +/// Takes effect for any commands queued after this function call. /// ///@param queue ///@param timeout /// -void mip_cmd_queue_set_base_reply_timeout(mip_cmd_queue* queue, timeout_type timeout) +void mip_cmd_queue_set_base_reply_timeout(mip_cmd_queue* queue, mip_timeout timeout) { queue->_base_timeout = timeout; } @@ -433,7 +484,75 @@ void mip_cmd_queue_set_base_reply_timeout(mip_cmd_queue* queue, timeout_type tim /// ///@returns The minimum time to wait for a reply to any command. /// -timeout_type mip_cmd_queue_base_reply_timeout(const mip_cmd_queue* queue) +mip_timeout mip_cmd_queue_base_reply_timeout(const mip_cmd_queue* queue) { return queue->_base_timeout; } + + +#ifdef MIP_ENABLE_DIAGNOSTICS + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the number of commands ever put into the queue. +/// +/// In most cases this is the number of commands sent to the device. +/// +uint16_t mip_cmd_queue_diagnostic_cmds_queued(const mip_cmd_queue* queue) +{ + return queue->_diag_cmds_queued; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the number of commands that have failed for any reason. +/// +uint16_t mip_cmd_queue_diagnostic_cmds_failed(const mip_cmd_queue* queue) +{ + return (uint16_t)queue->_diag_cmds_nacked + queue->_diag_cmds_failed + queue->_diag_cmds_timedout; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the number of successful commands. +/// +/// Same as mip_cmd_queue_diagnostic_cmd_acks(). +/// +uint16_t mip_cmd_queue_diagnostic_cmds_successful(const mip_cmd_queue* queue) +{ + return queue->_diag_cmds_acked; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the number of successful commands. +/// +/// Same as mip_cmd_queue_diagnostic_cmds_successful(). +/// +uint16_t mip_cmd_queue_diagnostic_cmd_acks(const mip_cmd_queue* queue) +{ + return queue->_diag_cmds_acked; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the number of commands nack'd by the device. +/// +uint16_t mip_cmd_queue_diagnostic_cmd_nacks(const mip_cmd_queue* queue) +{ + return queue->_diag_cmds_nacked; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the number of commands that did not receive a reply within the +/// time limit. +/// +uint16_t mip_cmd_queue_diagnostic_cmd_timeouts(const mip_cmd_queue* queue) +{ + return queue->_diag_cmds_timedout; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the number of command errors not caused by the device. +/// +uint16_t mip_cmd_queue_diagnostic_cmd_errors(const mip_cmd_queue* queue) +{ + return queue->_diag_cmds_failed; +} + +#endif // MIP_ENABLE_DIAGNOSTICS diff --git a/src/mip/mip_cmdqueue.h b/src/mip/mip_cmdqueue.h index 4515a1b25..868e735ec 100644 --- a/src/mip/mip_cmdqueue.h +++ b/src/mip/mip_cmdqueue.h @@ -43,9 +43,9 @@ typedef struct mip_pending_cmd struct mip_pending_cmd* _next; ///<@private Next command in the queue. uint8_t* _response_buffer; ///<@private Buffer for response data if response_descriptor != 0x00. union { ///<@private - timeout_type _extra_timeout; ///<@private If MIP_STATUS_PENDING: Duration to wait for reply, excluding base timeout time from the queue object. - timestamp_type _timeout_time; ///<@private If MIP_STATUS_WAITING: timestamp_type after which the command will be timed out. - timestamp_type _reply_time; ///<@private If MIP_STATUS_COMPLETED: timestamp_type from the packet containing the ack/nack. + mip_timeout _extra_timeout; ///<@private If MIP_STATUS_PENDING: Duration to wait for reply, excluding base timeout time from the queue object. + mip_timestamp _timeout_time; ///<@private If MIP_STATUS_WAITING: timestamp_type after which the command will be timed out. + mip_timestamp _reply_time; ///<@private If MIP_STATUS_COMPLETED: timestamp_type from the packet containing the ack/nack. }; uint8_t _descriptor_set; ///<@private Command descriptor set. uint8_t _field_descriptor; ///<@private Command field descriptor. @@ -58,16 +58,17 @@ typedef struct mip_pending_cmd } mip_pending_cmd; void mip_pending_cmd_init(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor); -void mip_pending_cmd_init_with_timeout(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, timeout_type additional_time); +void mip_pending_cmd_init_with_timeout(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, mip_timeout additional_time); void mip_pending_cmd_init_with_response(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, uint8_t response_descriptor, uint8_t* response_buffer, uint8_t response_buffer_size); -void mip_pending_cmd_init_full(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, uint8_t response_descriptor, uint8_t* response_buffer, uint8_t response_size, timeout_type additional_time); +void mip_pending_cmd_init_full(mip_pending_cmd* cmd, uint8_t descriptor_set, uint8_t field_descriptor, uint8_t response_descriptor, uint8_t* response_buffer, uint8_t response_size, mip_timeout additional_time); enum mip_cmd_result mip_pending_cmd_status(const mip_pending_cmd* cmd); - +uint8_t mip_pending_cmd_response_descriptor(const mip_pending_cmd* cmd); const uint8_t* mip_pending_cmd_response(const mip_pending_cmd* cmd); uint8_t mip_pending_cmd_response_length(const mip_pending_cmd* cmd); -bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, timestamp_type now); +int mip_pending_cmd_remaining_time(const mip_pending_cmd* cmd, mip_timestamp now); +bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, mip_timestamp now); ///@} //////////////////////////////////////////////////////////////////////////////// @@ -92,22 +93,42 @@ bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, timestamp_type no typedef struct mip_cmd_queue { mip_pending_cmd* _first_pending_cmd; - timeout_type _base_timeout; + mip_timeout _base_timeout; + +#ifdef MIP_ENABLE_DIAGNOSTICS + uint16_t _diag_cmds_queued; ///<@private Number of queued commands. + uint16_t _diag_cmds_acked; ///<@private Number of successful commands. + uint8_t _diag_cmds_nacked; ///<@private Number of commands failed by the device. + uint8_t _diag_cmds_timedout; ///<@private Number of commands that have timed out. + uint8_t _diag_cmds_failed; ///<@private Number of commands failed due to errors not from the device. +#endif // MIP_ENABLE_DIAGNOSTICS + } mip_cmd_queue; -void mip_cmd_queue_init(mip_cmd_queue* queue, timeout_type base_reply_timeout); +void mip_cmd_queue_init(mip_cmd_queue* queue, mip_timeout base_reply_timeout); void mip_cmd_queue_enqueue(mip_cmd_queue* queue, mip_pending_cmd* cmd); void mip_cmd_queue_dequeue(mip_cmd_queue* queue, mip_pending_cmd* cmd); void mip_cmd_queue_clear(mip_cmd_queue* queue); -void mip_cmd_queue_update(mip_cmd_queue* queue, timestamp_type timestamp); +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_set_base_reply_timeout(mip_cmd_queue* queue, timeout_type timeout); -timeout_type 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, timestamp_type timestamp); +#ifdef MIP_ENABLE_DIAGNOSTICS +uint16_t mip_cmd_queue_diagnostic_cmds_queued(const mip_cmd_queue* queue); +uint16_t mip_cmd_queue_diagnostic_cmds_failed(const mip_cmd_queue* queue); +uint16_t mip_cmd_queue_diagnostic_cmds_successful(const mip_cmd_queue* queue); +uint16_t mip_cmd_queue_diagnostic_cmd_acks(const mip_cmd_queue* queue); +uint16_t mip_cmd_queue_diagnostic_cmd_nacks(const mip_cmd_queue* queue); +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/mip/mip_device.cpp b/src/mip/mip_device.cpp index f1d36b234..d1d47968a 100644 --- a/src/mip/mip_device.cpp +++ b/src/mip/mip_device.cpp @@ -2,19 +2,50 @@ #include "mip_device.hpp" namespace mip { -namespace C { -extern "C" { -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, size_t* out_length, timestamp_type* timestamp_out) -{ - return static_cast(device)->recvFromDevice(buffer, max_length, out_length, timestamp_out); -} +//////////////////////////////////////////////////////////////////////////////// +///@fn Connection::sendToDevice +/// +///@brief Sends bytes to the device +/// +///@param data The data to send to the device +///@param length Length of data in bytes +//////////////////////////////////////////////////////////////////////////////// + +//////////////////////////////////////////////////////////////////////////////// +///@fn Connection::recvFromDevice +/// +///@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 +//////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length) + +//////////////////////////////////////////////////////////////////////////////// +///@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) { - return static_cast(device)->sendToDevice(data, length); + 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); } -} // extern "C" -} // namespace C } // namespace mip diff --git a/src/mip/mip_device.hpp b/src/mip/mip_device.hpp index 956a5359b..743186dd3 100644 --- a/src/mip/mip_device.hpp +++ b/src/mip/mip_device.hpp @@ -5,6 +5,7 @@ #include "definitions/descriptors.h" +#include namespace mip { @@ -21,6 +22,11 @@ struct Dispatcher : public C::mip_dispatcher ANY_DATA_SET = C::MIP_DISPATCH_ANY_DATA_SET, ANY_DESCRIPTOR = C::MIP_DISPATCH_ANY_DESCRIPTOR, }; + + void addHandler(DispatchHandler& handler) { C::mip_dispatcher_add_handler(this, &handler); } + void removeHandler(DispatchHandler& handler) { C::mip_dispatcher_remove_handler(this, &handler); } + + void removeAllHandlers() { C::mip_dispatcher_remove_all_handlers(this); } }; @@ -109,6 +115,9 @@ struct PendingCmd : public C::mip_pending_cmd /// 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); } @@ -135,8 +144,30 @@ template bool startCommand(C::mip_interface& device, C::mip_pending_c class Connection { public: - virtual bool sendToDevice(const uint8_t* data, size_t length) = 0; // Must be implemented by a derived class. - virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, size_t* length_out, Timestamp* timestamp) = 0; // Must be implemented by a derived class. + + 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; + }; @@ -150,9 +181,21 @@ class DeviceInterface : public C::mip_interface // Constructors // + ///@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) + { + 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) : mConnection(connection) { C::mip_interface_init(this, parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout); } + 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; @@ -160,49 +203,83 @@ class DeviceInterface : public C::mip_interface ~DeviceInterface() = default; // - // Accessors + // Callback functions // - ///@copydoc C::mip_interface_set_update_function + // C function callbacks + + C::mip_send_callback sendFunction() const { return C::mip_interface_send_function(this); } + C::mip_recv_callback recvFunction() const { return C::mip_interface_recv_function(this); } + C::mip_update_callback updateFunction() const { return C::mip_interface_update_function(this); } + + void setSendFunction (C::mip_send_callback callback) { C::mip_interface_set_send_function (this, callback); } + void setRecvFunction (C::mip_recv_callback callback) { C::mip_interface_set_recv_function (this, callback); } void setUpdateFunction(C::mip_update_callback function) { C::mip_interface_set_update_function(this, function); } - template + // free/nonmember function callbacks + + template + void setSendFunction(); + + template + void setRecvFunction(); + + template void setUpdateFunction(); + // derived member function callbacks + + template + void setSendFunction(); + + template + void setRecvFunction(); + + template + void setUpdateFunction(); + + // Separate class object callbacks + + template< + class T, + bool (T::*Send)(const uint8_t*, size_t), + bool (T::*Recv)(uint8_t*, size_t, Timeout, size_t*, Timestamp*), + bool (T::*Update)(Timeout) = nullptr + > + void setCallbacks(T* object); + + // + // General accessors + // + void setMaxPacketsPerPoll(unsigned int maxPackets) { C::mip_interface_set_max_packets_per_update(this, maxPackets); } unsigned int maxPacketsPerPoll() const { return C::mip_interface_max_packets_per_update(this); } Timeout baseReplyTimeout() const { return C::mip_cmd_queue_base_reply_timeout(&cmdQueue()); } void setBaseReplyTimeout(Timeout timeout) { C::mip_cmd_queue_set_base_reply_timeout(&cmdQueue(), timeout); } + 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 Connection* connection() const { return mConnection; } - void setConnection(Connection* connection) { mConnection = connection; } - // // Communications // - RemainingCount 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); } - - bool sendToDevice(const uint8_t* data, size_t length) { return mConnection->sendToDevice(data, length); } + 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 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); } - bool update(bool blocking=false) { return C::mip_interface_update(this, blocking); } - bool recvFromDevice(uint8_t* buffer, size_t max_length, size_t* length_out, Timestamp* timestamp) { return mConnection->recvFromDevice(buffer, max_length, length_out, timestamp); } - + 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 processUnparsedPackets() { C::mip_interface_process_unparsed_packets(this); } - CmdResult waitForReply(const C::mip_pending_cmd& cmd) { return C::mip_interface_wait_for_reply(this, &cmd); } - - bool defaultUpdate(bool blocking=false) { return C::mip_interface_default_update(this, blocking); } + CmdResult waitForReply(C::mip_pending_cmd& cmd) { return C::mip_interface_wait_for_reply(this, &cmd); } // // Data Callbacks @@ -212,10 +289,10 @@ class DeviceInterface : 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); @@ -229,9 +306,15 @@ class DeviceInterface : public C::mip_interface template void registerDataCallback(C::mip_dispatch_handler& handler, void* userData=nullptr, uint8_t descriptorSet=DataField::DESCRIPTOR_SET); + template + void registerDataCallback(C::mip_dispatch_handler& handler, void* userData=nullptr, uint8_t descriptorSet=DataField::DESCRIPTOR_SET); + template void registerDataCallback(C::mip_dispatch_handler& handler, Object* object, uint8_t descriptorSet=DataField::DESCRIPTOR_SET); + template + void registerDataCallback(C::mip_dispatch_handler& handler, Object* object, uint8_t descriptorSet=DataField::DESCRIPTOR_SET); + template void registerExtractor(C::mip_dispatch_handler& handler, DataField* field, uint8_t descriptorSet=DataField::DESCRIPTOR_SET); @@ -255,36 +338,198 @@ class DeviceInterface : public C::mip_interface // template // bool startCommand(PendingCmd& pending, const Cmd& cmd, uint8_t* responseBuffer, uint8_t responseBufferSize, Timeout additionalTime=0) { return mip::startCommand(pending, cmd, responseBuffer, responseBufferSize, additionalTime); } - -private: - Connection* mConnection; }; + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the send callback function (free function version). +/// +///@tparam Send A compile-time pointer to the callback function. +/// +template +void DeviceInterface::setSendFunction() +{ + setSendFunction([](C::mip_interface* device, const uint8_t* data, size_t length){ + return (*Send)(*static_cast(device), data, length); + }); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the receive callback function (free function version). +/// +///@tparam Send A compile-time pointer to the callback function. +/// +template +void DeviceInterface::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); + }); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the update callback function (free function version). +/// +///@tparam Send A compile-time pointer to the callback function. +/// +template +void DeviceInterface::setUpdateFunction() +{ + setUpdateFunction([](C::mip_interface* device, C::mip_timeout wait_time){ + return (*Update)(*static_cast(device), wait_time); + }); +} + + //////////////////////////////////////////////////////////////////////////////// -///@brief Sets the update function to a function taking a MipDevice reference. +///@brief Sets the send callback function (derived member function version). +/// +///@tparam Derived Derived class type. Must inherit from DeviceInterface. +///@tparam Send Compile-time pointer to member function of Derived. /// ///@code{.cpp} -/// bool updateDevice(DeviceInterface& device, bool blocking) +/// class MyClass : public mip::DeviceInterface /// { -/// return device.defaultUpdate(blocking); -/// } +/// 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); +/// }; /// -/// device.setUpdateFunction<&updateDevice>(); +/// MyClass instance; +/// instance.setSendFunction(); +/// instance.setRecvFunction(); +/// +/// instance.setCallbacks(connection); ///@endcode /// -template + +template +void DeviceInterface::setSendFunction() +{ + static_assert(std::is_base_of::value, "Derived must be derived from C::mip_interface."); + + setSendFunction( + [](C::mip_interface* device, const uint8_t* data, size_t length) + { + return (static_cast(device)->*Send)(data, length); + } + ); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the receive callback function (derived member function version). +/// +///@tparam Derived Derived class type. Must inherit from DeviceInterface. +///@tparam Recv Compile-time pointer to member function of Derived. +/// +///@see DeviceInterface::setSendFunction() +/// +template +void DeviceInterface::setRecvFunction() +{ + static_assert(std::is_base_of::value, "Derived must be derived from C::mip_interface."); + + setRecvFunction( + [](C::mip_interface* device, uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, Timestamp* timestamp_out) + { + return (static_cast(device)->*Recv)(buffer, max_length, wait_time, length_out, timestamp_out); + } + ); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the update callback function (derived member function version). +/// +///@tparam Derived Derived class type. Must inherit from DeviceInterface. +///@tparam Update Compile-time pointer to member function of Derived. +/// +///@see DeviceInterface::setSendFunction() +/// +template void DeviceInterface::setUpdateFunction() { + static_assert(std::is_base_of::value, "Derived must be derived from C::mip_interface."); + setUpdateFunction( - [](C::mip_interface* device, bool blocking)->bool + [](C::mip_interface* device, C::mip_timeout wait_time)->bool { - return Function(*static_cast(device), blocking); + return (static_cast(device)->*Update)(wait_time); } ); } +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the callback functions to a common class object. +/// +///@tparam T +/// A class type. +/// +///@tparam Send +/// A member function pointer for sending bytes to the device. +/// May be NULL. +/// +///@tparam Recv +/// A member function pointer for receiving bytes from the device. +/// May be NULL. +/// +///@tparam Update +/// A member function pointer for updating the device. +/// If both this and Recv are NULL, no update function is set. +/// If Update is NULL but Recv is not, the default update function +/// is used instead. +/// +///@param object +/// An instance of T. The interface's user pointer will be set to this +/// value. All of the callbacks will be invoked on this instance. +/// +///@code{.cpp} +/// class DeviceConnection +/// { +/// bool send(const uint8_t* data, size_t length); +/// bool recv(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, Timestamp* timestamp_out); +/// }; +/// +/// DeviceConnection connection; +/// mip::DeviceInterface interface; +/// +/// interface.setCallbacks(&connection); +///@endcode +/// +template< + class T, + bool (T::*Send)(const uint8_t*, size_t), + bool (T::*Recv)(uint8_t*, size_t, Timeout, size_t*, Timestamp*), + bool (T::*Update)(Timeout) +> +void DeviceInterface::setCallbacks(T* object) +{ + auto send = [](C::mip_interface* device, const uint8_t* data, size_t size) + { + return (static_cast(mip_interface_user_pointer(device))->*Send)(data, size); + }; + 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) + { + return (static_cast(mip_interface_user_pointer(device))->*Recv)(buffer, max_length, wait_time, length_out, timestamp_out); + }; + auto update = [](C::mip_interface* device, C::mip_timeout wait_time) + { + return (static_cast(mip_interface_user_pointer(device))->*Update)(wait_time); + }; + + C::mip_interface_set_user_pointer(this, object); + C::mip_interface_set_send_function(this, Send != nullptr ? send : nullptr); + C::mip_interface_set_recv_function(this, Recv != nullptr ? recv : nullptr); + + if( Update != nullptr ) + C::mip_interface_set_update_function(this, update); + else if( Recv != nullptr ) + C::mip_interface_set_update_function(this, &C::mip_interface_default_update); + else + C::mip_interface_set_update_function(this, nullptr); +} + + //////////////////////////////////////////////////////////////////////////////// ///@brief Registers a packet callback (free function version). /// @@ -298,7 +543,7 @@ void DeviceInterface::setUpdateFunction() /// /// Example usage: ///@code{.cpp} -/// void handle_packet(void* context, const Packet& packet, Timestamp timestamp) +/// void handle_packet(void* context, const PacketRef& packet, Timestamp timestamp) /// { /// // Use the packet data /// } @@ -315,12 +560,12 @@ void DeviceInterface::setUpdateFunction() /// ///@endcode /// -template +template void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, void* userData) { auto callback = [](void* context, const C::mip_packet* packet, Timestamp timestamp) { - Callback(context, Packet(*packet), timestamp); + Callback(context, PacketRef(*packet), timestamp); }; registerPacketCallback(handler, descriptorSet, afterFields, callback, userData); @@ -342,7 +587,7 @@ void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, u ///@code{.cpp} /// class MySystem /// { -/// void handlePacket(const Packet& packet, Timestamp timestamp) +/// void handlePacket(const PacketRef& packet, Timestamp timestamp) /// { /// } /// @@ -357,13 +602,13 @@ void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, u /// }; ///@endcode /// -template +template void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, Object* object) { - auto callback = [](void* pointer, const Packet& packet, Timestamp timestamp) + auto callback = [](void* pointer, const mip::C::mip_packet* packet, Timestamp timestamp) { Object* obj = static_cast(pointer); - (obj->*Callback)(Packet(packet), timestamp); + (obj->*Callback)(PacketRef(*packet), timestamp); }; registerPacketCallback(handler, descriptorSet, afterFields, callback, object); @@ -454,7 +699,6 @@ void DeviceInterface::registerFieldCallback(C::mip_dispatch_handler& handler, ui registerFieldCallback(handler, descriptorSet, fieldDescriptor, callback, object); } - //////////////////////////////////////////////////////////////////////////////// ///@brief Registers a data callback (free function version). /// @@ -473,7 +717,7 @@ void DeviceInterface::registerFieldCallback(C::mip_dispatch_handler& handler, ui /// /// Example usage: ///@code{.cpp} -/// void handle_packet(void* context, const Packet& packet, Timestamp timestamp) +/// void handle_packet(void* context, const PacketRef& packet, Timestamp timestamp) /// { /// // Use the packet data /// } @@ -514,6 +758,65 @@ void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, voi registerFieldCallback(handler, descriptorSet, DataField::FIELD_DESCRIPTOR, callback, userData); } +//////////////////////////////////////////////////////////////////////////////// +///@brief Registers a data callback (free function version). +/// +///@tparam Callback A pointer to the function to call. This must be a constant +/// function pointer. +/// +///@param handler +/// This must exist as long as the hander 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. +/// +/// Example usage: +///@code{.cpp} +/// void handle_packet(void* context, uint8_t descriptorSet, const PacketRef& packet, Timestamp timestamp) +/// { +/// // Use the packet data +/// } +/// +/// DeviceInterface device; +/// DispatchHandler handler; +/// +/// void setup() +/// { +/// // Set up device... +/// +/// device.registerDataCallback<&handle_packet>(handler, descriptorSet, nullptr); +/// } +/// +///@endcode +/// +template +void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, void* userData, uint8_t descriptorSet) +{ + assert(descriptorSet != 0x00); + if(descriptorSet == 0x00) + return; + + assert(descriptorSet != 0xFF); // Descriptor set must be specified for shared data. + if(descriptorSet == 0xFF) + return; + + auto callback = [](void* context, const C::mip_field* field, Timestamp timestamp) + { + DataField data; + + bool ok = Field(*field).extract(data); + assert(ok); (void)ok; + + Callback(context, data, mip_field_descriptor_set(field), timestamp); + }; + + registerFieldCallback(handler, descriptorSet, DataField::FIELD_DESCRIPTOR, callback, userData); +} + //////////////////////////////////////////////////////////////////////////////// ///@brief Registers a data callback (member function version). /// @@ -575,6 +878,67 @@ void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, Obj registerFieldCallback(handler, descriptorSet, DataField::FIELD_DESCRIPTOR, callback, object); } +//////////////////////////////////////////////////////////////////////////////// +///@brief Registers a data callback (member function version). +/// +///@tparam Callback A pointer to the function to call. This must be a constant +/// member function pointer. +/// +///@param handler +/// This must exist as long as the hander remains registered. +/// +///@param object +/// A pointer to the object. The object must exist while the handler +/// remains registered. +/// +///@param descriptorSet +/// If specified, overrides the descriptor set. Intended to be used with +/// with shared data quantities. +/// +/// Example usage: +///@code{.cpp} +/// class MySystem +/// { +/// void handleAccel(const ScaledAccel& accel, uint8_t descriptorSet, Timestamp timestamp) +/// { +/// } +/// +/// void setup() +/// { +/// // setup device... +/// device.registerDataHandler(accelHandler, this); +/// } +/// +/// DeviceInterface device; +/// DispatchHandler accelHandler; +/// }; +///@endcode +/// +template +void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, Object* object, uint8_t descriptorSet) +{ + assert(descriptorSet != 0x00); + if(descriptorSet == 0x00) + return; + + assert(descriptorSet != 0xFF); // Descriptor set must be specified for shared data. + if(descriptorSet == 0xFF) + return; + + auto callback = [](void* pointer, const C::mip_field* field, Timestamp timestamp) + { + DataField data; + + bool ok = Field(*field).extract(data); + assert(ok); (void)ok; + + Object* obj = static_cast(pointer); + (obj->*Callback)(data, mip_field_descriptor_set(field), timestamp); + }; + + registerFieldCallback(handler, descriptorSet, DataField::FIELD_DESCRIPTOR, callback, object); +} + template void DeviceInterface::registerExtractor(C::mip_dispatch_handler& handler, DataField* field, uint8_t descriptorSet) @@ -591,8 +955,7 @@ void DeviceInterface::registerExtractor(C::mip_dispatch_handler& handler, DataFi template CmdResult runCommand(C::mip_interface& device, const Cmd& cmd, Timeout additionalTime) { - uint8_t buffer[PACKET_LENGTH_MAX]; - Packet packet = Packet::createFromField(buffer, sizeof(buffer), cmd); + PacketBuf packet(cmd); C::mip_pending_cmd pending; C::mip_pending_cmd_init_with_timeout(&pending, Cmd::DESCRIPTOR_SET, Cmd::FIELD_DESCRIPTOR, additionalTime); @@ -610,11 +973,10 @@ CmdResult runCommand(C::mip_interface& device, const Args&&... args, Timeout add template CmdResult runCommand(C::mip_interface& device, const Cmd& cmd, typename Cmd::Response& response, Timeout additionalTime) { - uint8_t buffer[PACKET_LENGTH_MAX]; - Packet packet = Packet::createFromField(buffer, sizeof(buffer), cmd); + PacketBuf packet(cmd); C::mip_pending_cmd pending; - C::mip_pending_cmd_init_full(&pending, Cmd::DESCRIPTOR_SET, Cmd::FIELD_DESCRIPTOR, Cmd::Response::FIELD_DESCRIPTOR, buffer, FIELD_PAYLOAD_LENGTH_MAX, additionalTime); + C::mip_pending_cmd_init_full(&pending, Cmd::DESCRIPTOR_SET, Cmd::FIELD_DESCRIPTOR, Cmd::Response::FIELD_DESCRIPTOR, packet.buffer(), FIELD_PAYLOAD_LENGTH_MAX, additionalTime); CmdResult result = C::mip_interface_run_command_packet(&device, &packet, &pending); if( result != C::MIP_ACK_OK ) @@ -622,15 +984,14 @@ CmdResult runCommand(C::mip_interface& device, const Cmd& cmd, typename Cmd::Res size_t responseLength = C::mip_pending_cmd_response_length(&pending); - return extract(response, buffer, responseLength, 0) ? CmdResult::ACK_OK : CmdResult::STATUS_ERROR; + return extract(response, packet.buffer(), responseLength, 0) ? CmdResult::ACK_OK : CmdResult::STATUS_ERROR; } template bool startCommand(C::mip_interface& device, C::mip_pending_cmd& pending, const Cmd& cmd, Timeout additionalTime) { - uint8_t buffer[PACKET_LENGTH_MAX]; - Packet packet = Packet::createFromField(buffer, sizeof(buffer), cmd); + PacketBuf packet(cmd); C::mip_pending_cmd_init_with_timeout(&pending, Cmd::DESCRIPTOR_SET, Cmd::FIELD_DESCRIPTOR, additionalTime); @@ -640,8 +1001,7 @@ bool startCommand(C::mip_interface& device, C::mip_pending_cmd& pending, const C //template //bool startCommand(C::mip_interface& device, C::mip_pending_cmd& pending, const Cmd& cmd, uint8_t* responseBuffer, uint8_t responseBufferSize, Timeout additionalTime) //{ -// uint8_t buffer[PACKET_LENGTH_MAX]; -// Packet packet = Packet::createFromField(buffer, sizeof(buffer), cmd); +// PacketBuf packet(cmd); // // C::mip_pending_cmd_init_full(&pending, Cmd::descriptorSet, Cmd::fieldDescriptor, Cmd::Response::fieldDescriptor, responseBuffer, responseBufferSize, additionalTime); // diff --git a/src/mip/mip_dispatch.c b/src/mip/mip_dispatch.c index 811ba84b2..251e1770e 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, timestamp_type timestamp, bool post) +static void mip_dispatcher_call_packet_callbacks(mip_dispatcher* self, const mip_packet* packet, mip_timestamp timestamp, bool post) { const uint8_t descriptor_set = mip_packet_descriptor_set(packet); @@ -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, timestamp_type timestamp) +static void mip_dispatcher_call_field_callbacks(mip_dispatcher* self, const mip_field* field, mip_timestamp timestamp) { const uint8_t descriptor_set = mip_field_descriptor_set(field); const uint8_t field_descriptor = mip_field_field_descriptor(field); @@ -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, timestamp_type timestamp) +void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet* 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 09357fa88..59b02dbbf 100644 --- a/src/mip/mip_dispatch.h +++ b/src/mip/mip_dispatch.h @@ -35,7 +35,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, timestamp_type timestamp); +typedef void (*mip_dispatch_packet_callback)(void* context, const mip_packet* packet, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for field-level callbacks. @@ -44,7 +44,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, timestamp_type timestamp); +typedef void (*mip_dispatch_field_callback )(void* context, const mip_field* field, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for extraction callbacks. @@ -129,7 +129,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, timestamp_type timestamp); +void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet* packet, mip_timestamp timestamp); ///@} ///@} diff --git a/src/mip/mip_field.c b/src/mip/mip_field.c index e95336486..de7548430 100644 --- a/src/mip/mip_field.c +++ b/src/mip/mip_field.c @@ -117,10 +117,9 @@ mip_field mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, { mip_field field; - field._payload = header + MIP_INDEX_FIELD_PAYLOAD; - field._descriptor_set = descriptor_set; - // Default invalid values. + field._payload = NULL; + field._descriptor_set = descriptor_set; field._payload_length = 0; field._field_descriptor = 0x00; // This makes the field invalid. field._remaining_length = 0; @@ -139,6 +138,7 @@ mip_field mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, { field._field_descriptor = header[MIP_INDEX_FIELD_DESC]; field._payload_length = field_length - MIP_FIELD_HEADER_LENGTH; + field._payload = header + MIP_INDEX_FIELD_PAYLOAD; field._remaining_length = total_length - field_length; } } @@ -178,6 +178,9 @@ mip_field mip_field_first_from_packet(const mip_packet* packet) /// mip_field mip_field_next_after(const mip_field* field) { + // Payload length must be zero if payload is NULL. + assert(!(field->_payload == NULL) || (field->_payload_length == 0)); + const uint8_t* next_header = field->_payload + field->_payload_length; return mip_field_from_header_ptr(next_header, field->_remaining_length, field->_descriptor_set); diff --git a/src/mip/mip_interface.c b/src/mip/mip_interface.c index 03ca1f7dd..586b7689a 100644 --- a/src/mip/mip_interface.c +++ b/src/mip/mip_interface.c @@ -10,20 +10,113 @@ #include //////////////////////////////////////////////////////////////////////////////// -///@brief Wrapper around mip_interface_receive_packet for use with mip_parser. +///@typedef mip::C::mip_send_callback /// -///@param device Void pointer to the device. Must be a mip_interface pointer. -///@param packet MIP Packet from the parser. -///@param timestamp timestamp_type of the packet. +///@brief Called from mip_interface_send_to_device() to send data to the device port. +/// The application should forward the data to the device port (e.g. a +/// serial port, TCP connection, etc). /// -///@returns True +/// Applications should avoid introducing significant transmission delays as it +/// may cause excessive command response times or timeouts. +/// +///@param device +/// A pointer to the device interface. Applications can use the user data +/// pointer to access additional information such as the port handle. +///@param data +/// Buffer containing the data to be transmitted to the device. +///@param length +/// Length of data to transmit. +/// +///@return True if all of the data was successfully transmitted. +///@return False if an error occurred and some or all data was definitely unable +/// to be transmitted. +///@return Applications should prefer returning true if success is uncertain +/// since command timeouts will help detect failed transmissions. If this +/// function returns false, the associated command will fail with +/// CmdResult::STATUS_ERROR. +/// +///@note +/// +///@note The data buffer is almost always a MIP packet. However, there are some +/// cases where this is not true and an application should not rely on it. +/// +///@see mip_interface_send_to_device /// -bool mip_interface_parse_callback(void* device, const mip_packet* packet, timestamp_type timestamp) -{ - mip_interface_receive_packet(device, packet, timestamp); - return true; -} +//////////////////////////////////////////////////////////////////////////////// +///@typedef mip::C::mip_recv_callback +/// +///@brief Called from mip_interface_recv_from_device() to receive data from the +/// device port. +/// +/// This is called indirectly through mip_interface_update() to poll for new +/// data and command responses. For single-threaded applications, it will be +/// called while waiting for command replies. +/// +/// +///@param device +/// A pointer to the device interface. Applications can use the user data +/// pointer to access additional information such as the port handle. +/// +///@param buffer +/// Buffer to fill with data. Should be allocated before this function is called. +/// +///@param max_length +/// Max number of bytes that can be read into the buffer. +/// +///@param wait_time +/// Time to wait for data from the device. The actual time waited may +/// be less than wait_time, but it should not significantly exceed this value. +/// +///@param[out] length_out +/// Number of bytes actually read into the buffer. +/// +///@param[out] timestamp_out +/// Timestamp the data was received. +/// +///@returns True if successful, even if no data is received. +///@returns False if the port cannot be read or some other error occurs (e.g. +/// if the port is closed). +/// +///@note Except in case of error (i.e. returning false), the timestamp must be +/// set even if no data is received. This is required to allow commands +/// to time out. +/// +///@note Applications may sleep the thread or enter a low-power state while +/// waiting for data. On posix-like (e.g. desktop) systems, applications +/// should call read() with a maximum timeout of wait_time. +/// If the actual wait time is less than the requested duration, this +/// function may be called again by the MIP SDK to wait the remaining time. +/// If the actual wait time exceeds wait_time, command timeouts may take +/// longer than intended. +/// +///@see mip_interface_recv_from_device +/// + +//////////////////////////////////////////////////////////////////////////////// +///@typedef mip::C::mip_update_callback +/// +///@brief Callback function typedef for custom update behavior. +/// +/// This function is called whenever data should be parsed from the port: +///@li While waiting for command responses +///@li To check for new data packets +/// +/// Generally an application should call mip_interface_recv_from_device() from +/// within this callback and pass the data to mip_interface_receive_bytes(). +/// Most applications can set this callback to mip_interface_default_update(). +/// +///@param device +/// The mip_interface object being updated. +///@param timeout +/// Amount of time to wait for data from the device. This will be zero +/// when checking for data and nonzero when waiting for commands. +/// +///@returns True if successful (even if no data is received). +///@returns False if an error occurs and the port cannot be read (e.g. if the +/// port is closed). Returning false will cause any pending commands to +/// fail with a status error code. +/// //////////////////////////////////////////////////////////////////////////////// ///@brief Initialize the mip_interface components. @@ -38,13 +131,29 @@ bool mip_interface_parse_callback(void* device, const mip_packet* packet, timest /// Maximum length of time to wait for the end of a MIP packet. See mip_parser_init(). ///@param base_reply_timeout /// Minimum time for all commands. See mip_cmd_queue_init(). -/// -void mip_interface_init(mip_interface* device, uint8_t* parse_buffer, size_t parse_buffer_size, timeout_type parse_timeout, timeout_type base_reply_timeout) +///@param send +/// A callback which is called to send data to the device. +///@param recv +/// A callback which is called when data needs to be read from the device. +///@param update +/// Optional callback which is called to perform routine tasks such as +/// checking for command timeouts. Defaults to mip_interface_default_update. +///@param user_pointer +/// Optional pointer which is passed to the send, recv, and update callbacks. +/// +void mip_interface_init( + mip_interface* device, uint8_t* parse_buffer, size_t parse_buffer_size, + mip_timeout parse_timeout, mip_timeout base_reply_timeout, + mip_send_callback send, mip_recv_callback recv, + mip_update_callback update, void* user_pointer) { mip_parser_init(&device->_parser, parse_buffer, parse_buffer_size, &mip_interface_parse_callback, device, parse_timeout); device->_max_update_pkts = MIPPARSER_UNLIMITED_PACKETS; - device->_update_function = &mip_interface_default_update; + device->_send_callback = send; + device->_recv_callback = recv; + device->_update_callback = update; + device->_user_pointer = user_pointer; mip_cmd_queue_init(&device->_queue, base_reply_timeout); @@ -52,6 +161,66 @@ void mip_interface_init(mip_interface* device, uint8_t* parse_buffer, size_t par } +//////////////////////////////////////////////////////////////////////////////// +// +// Accessors +// +//////////////////////////////////////////////////////////////////////////////// + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the send callback function. +/// +///@param device +/// +///@param callback +/// Function which sends raw bytes to the device. This can be NULL if no +/// commands will be issued (they would fail). +/// +void mip_interface_set_send_function(mip_interface* device, mip_send_callback callback) +{ + device->_send_callback = callback; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the send function pointer. +/// +///@param device +/// +///@returns The send callback function. May be NULL. +/// +mip_send_callback mip_interface_send_function(const mip_interface* device) +{ + return device->_send_callback; +} + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets the receive callback function. +/// +///@param device +/// +///@param callback +/// Function which gets data from the device connection. +/// If this is NULL then commands will fail and no data will be received. +/// +void mip_interface_set_recv_function(mip_interface* device, mip_recv_callback callback) +{ + device->_recv_callback = callback; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the receive function pointer. +/// +///@param device +/// +///@returns The receive callback function. May be NULL. +/// +mip_recv_callback mip_interface_recv_function(const mip_interface* device) +{ + return device->_recv_callback; +} + //////////////////////////////////////////////////////////////////////////////// ///@brief Sets the update function. @@ -63,25 +232,26 @@ void mip_interface_init(mip_interface* device, uint8_t* parse_buffer, size_t par /// ///@param device /// -///@param function +///@param callback /// Update function to call when polling the device for data. /// If this is NULL, then update calls will fail and no data or /// or command replies will be received. /// -void mip_interface_set_update_function(struct mip_interface* device, mip_update_callback function) +void mip_interface_set_update_function(mip_interface* device, mip_update_callback callback) { - device->_update_function = function; + device->_update_callback = callback; } + //////////////////////////////////////////////////////////////////////////////// ///@brief Gets the update function pointer. /// ///@returns The update function. Defaults to mip_interface_default_update. May /// be NULL. /// -mip_update_callback mip_interface_update_function(struct mip_interface* device) +mip_update_callback mip_interface_update_function(const mip_interface* device) { - return device->_update_function; + return device->_update_callback; } @@ -138,6 +308,66 @@ void mip_interface_set_max_packets_per_update(mip_interface* device, unsigned in } +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the MIP parser for the device. +/// +mip_parser* mip_interface_parser(mip_interface* device) +{ + return &device->_parser; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the commmand queue for the device. +/// +mip_cmd_queue* mip_interface_cmd_queue(mip_interface* device) +{ + return &device->_queue; +} + + +//////////////////////////////////////////////////////////////////////////////// +// +// Communications +// +//////////////////////////////////////////////////////////////////////////////// + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Sends data to the port (i.e. from this library to the physical device). +/// +///@param device The mip_interface object. +///@param data Data to be sent. +///@param length Length of data. +/// +///@returns True if the data was sent successfully. +///@returns False if the send callback is NULL. +///@returns False if some or all data could not be sent. +/// +/// This is called whenever bytes must be sent to the physical device. +/// +bool mip_interface_send_to_device(mip_interface* device, const uint8_t* data, size_t length) +{ + return device->_send_callback && device->_send_callback(device, data, length); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Checks for data at the port and reads it into buffer. +/// +///@param device +///@param buffer A place to store the data. +///@param max_length Maximum number of bytes to read into buffer. +///@param wait_time Maximum time to wait for data. May be 0. +///@param length_out The number of bytes successfully read into buffer. +///@param timestamp_out The timestamp of the received data. +/// +///@returns True if successful (even if 0 bytes were read). +///@returns False if the receive callback is NULL. +///@returns False if the receive callback failed (i.e. if it returned false). +/// +bool mip_interface_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* length_out, mip_timestamp* timestamp_out) +{ + return device->_recv_callback && device->_recv_callback(device, buffer, max_length, wait_time, length_out, timestamp_out); +} //////////////////////////////////////////////////////////////////////////////// ///@brief Call to process data from the device. @@ -145,80 +375,69 @@ void mip_interface_set_max_packets_per_update(mip_interface* device, unsigned in /// This function is also called while waiting for command replies. /// /// Call this periodically to process packets received from the device. It -/// should be called at a suitably-high rate to prevent the connection buffers +/// should be called at a suitably high rate to prevent the connection buffers /// from overflowing. The update rate affects the reception timestamp resolution. /// ///@param device /// -///@param blocking -/// This is true when called from within a blocking command function. -/// Applications should generally set this to false, e.g. when calling -/// this to process incoming data packets. +///@param wait_time +/// Time to wait for data from the device. This will be nonzero when +/// waiting for command replies. Applications calling this function +/// can pass 0 to avoid blocking when checking for new data. /// ///@returns true if operation should continue, or false if the device cannot be /// updated (e.g. if the serial port is not open). /// -bool mip_interface_update(struct mip_interface* device, bool blocking) +bool mip_interface_update(struct mip_interface* device, mip_timeout wait_time) { - if( !device->_update_function ) + if( !device->_update_callback ) return false; - return device->_update_function(device, blocking); + return device->_update_callback(device, wait_time); } + //////////////////////////////////////////////////////////////////////////////// ///@brief Polls the port for new data or command replies. /// /// This is the default choice for the user update function. It ignores the /// blocking flag and always reads data from the device. /// -///@param device The mip_interface object. -///@param blocking Ignored. +///@param device +/// +///@param wait_time +/// Time to wait for data to be received. Passed directly to +/// mip_interface_recv_from_device(). /// ///@returns The value returned by mip_interface_user_recv_from_device. /// -bool mip_interface_default_update(struct mip_interface* device, bool blocking) +bool mip_interface_default_update(struct mip_interface* device, mip_timeout wait_time) { - (void)blocking; + if( !device->_recv_callback ) + return false; uint8_t* ptr; mip_parser* parser = mip_interface_parser(device); size_t max_count = mip_parser_get_write_ptr(parser, &ptr); - size_t count = 0; - timestamp_type timestamp = 0; - if ( !mip_interface_user_recv_from_device(device, ptr, max_count, &count, ×tamp) ) + size_t count = 0; + mip_timestamp timestamp = 0; + if ( !mip_interface_recv_from_device(device, ptr, max_count, wait_time, &count, ×tamp) ) return false; assert(count <= max_count); mip_parser_process_written(parser, count, timestamp, 0); + mip_cmd_queue_update(mip_interface_cmd_queue(device), timestamp); - return true; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Sends data to the port (i.e. from this library to the physical device). -/// -///@param device The mip_interface object. -///@param data Data to be sent. -///@param length Length of data. -/// -///@returns True if the data was sent successfully, false if some or all data -/// could not be sent. -/// -/// This is called whenever bytes must be sent to the physical device. -/// -bool mip_interface_send_to_device(mip_interface* device, const uint8_t* data, size_t length) -{ - return mip_interface_user_send_to_device(device, data, length); + return true; } //////////////////////////////////////////////////////////////////////////////// -///@brief Receive data from the port (i.e. the physical device) into the parser. +///@brief Passes data from the device into the parser. /// ///@param device /// @@ -232,12 +451,11 @@ bool mip_interface_send_to_device(mip_interface* device, const uint8_t* data, si ///@returns The amount of data which couldn't be processed due to the limit on /// number of packets per parse call. Normally the result is 0. /// -remaining_count mip_interface_receive_bytes(mip_interface* device, const uint8_t* data, size_t length, timestamp_type timestamp) +size_t mip_interface_receive_bytes(mip_interface* device, const uint8_t* data, size_t length, mip_timestamp timestamp) { return mip_parser_parse(&device->_parser, data, length, timestamp, device->_max_update_pkts); } - //////////////////////////////////////////////////////////////////////////////// ///@brief Process more packets from the internal buffer. /// @@ -265,28 +483,34 @@ 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, timestamp_type timestamp) +void mip_interface_receive_packet(mip_interface* device, const mip_packet* packet, mip_timestamp timestamp) { mip_cmd_queue_process_packet(&device->_queue, packet, timestamp); mip_dispatcher_dispatch_packet(&device->_dispatcher, packet, timestamp); } - //////////////////////////////////////////////////////////////////////////////// -///@brief Returns the MIP parser for the device. +///@brief Wrapper around mip_interface_receive_packet for use with mip_parser. /// -mip_parser* mip_interface_parser(mip_interface* device) +///@param device Void pointer to the device. Must be a mip_interface pointer. +///@param packet MIP Packet from the parser. +///@param timestamp timestamp_type of the packet. +/// +///@returns True +/// +bool mip_interface_parse_callback(void* device, const mip_packet* packet, mip_timestamp timestamp) { - return &device->_parser; + mip_interface_receive_packet(device, packet, timestamp); + + return true; } + +//////////////////////////////////////////////////////////////////////////////// +// +// Command and data processing +// //////////////////////////////////////////////////////////////////////////////// -///@brief Returns the commmand queue for the device. -/// -mip_cmd_queue* mip_interface_cmd_queue(mip_interface* device) -{ - return &device->_queue; -} //////////////////////////////////////////////////////////////////////////////// @@ -297,13 +521,28 @@ mip_cmd_queue* mip_interface_cmd_queue(mip_interface* device) /// ///@returns The final status of the command. /// -enum mip_cmd_result mip_interface_wait_for_reply(mip_interface* device, const mip_pending_cmd* cmd) +enum mip_cmd_result mip_interface_wait_for_reply(mip_interface* device, mip_pending_cmd* cmd) { enum mip_cmd_result status; while( !mip_cmd_result_is_finished(status = mip_pending_cmd_status(cmd)) ) { if( !mip_interface_update(device, true) ) + { + // When this function returns the pending command may be deallocated and the + // queue will have a dangling pointer. Therefore, the command must be manually + // errored out and de-queued. + // + // Note: This fix can still cause a race condition in multithreaded apps if the + // update thread happens to run right before the cmd is dequeued. The user is + // advised to not fail the update callback when another thread is handling + // reception, unless that thread is not running. Generally such updates shouldn't + // fail as long as the other thread is working normally anyway. + + mip_cmd_queue_dequeue(mip_interface_cmd_queue(device), cmd); + cmd->_status = MIP_STATUS_ERROR; + return MIP_STATUS_ERROR; + } } return status; } @@ -332,11 +571,28 @@ enum mip_cmd_result mip_interface_run_command(mip_interface* device, uint8_t des } //////////////////////////////////////////////////////////////////////////////// -///@copydoc mip_interface_run_command +///@brief Runs a command using a pre-serialized payload. /// +///@param device +///@param descriptor_set +/// Command descriptor set. +///@param cmd_descriptor +/// Command field descriptor. +///@param cmd_data +/// Optional payload data. May be NULL if cmd_length == 0. +///@param cmd_length +/// Length of the command payload (parameters). ///@param response_descriptor /// Descriptor of the response data. May be MIP_INVALID_FIELD_DESCRIPTOR /// if no response is expected. +///@param response_buffer +/// Buffer to hold response data. Can be the same as the command data buffer. +/// Can be NULL if response_descriptor is MIP_INVALID_FIELD_DESCRIPTOR. +///@param[in,out] response_length_inout +/// As input, the size of response buffer and max response length. +/// As output, returns the actual length of the response data. +/// +///@returns mip_cmd_result /// enum mip_cmd_result mip_interface_run_command_with_response(mip_interface* device, uint8_t descriptor_set, uint8_t cmd_descriptor, const uint8_t* cmd_data, uint8_t cmd_length, diff --git a/src/mip/mip_interface.h b/src/mip/mip_interface.h index dc9e10ea4..c3d2868ed 100644 --- a/src/mip/mip_interface.h +++ b/src/mip/mip_interface.h @@ -32,53 +32,54 @@ extern "C" { struct mip_interface; -//////////////////////////////////////////////////////////////////////////////// -///@brief Callback function typedef for custom update behavior. -/// -///@param device The mip_interface object being updated. -///@param blocking True if called from within a blocking command function. -/// -///@returns False if an error occurs and the port cannot be read (e.g. if the -/// port is closed). Returning false will cause any pending commands to -/// fail with a status error code. -///@returns True if successful (even if no data is received). -/// -typedef bool (*mip_update_callback)(struct mip_interface* device, bool blocking); +// Documentation is in source file. +typedef bool (*mip_send_callback)(struct mip_interface* device, const uint8_t* data, size_t length); +typedef bool (*mip_recv_callback)(struct mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* length_out, mip_timestamp* timestamp_out); +typedef bool (*mip_update_callback)(struct mip_interface* device, mip_timeout timeout); + //////////////////////////////////////////////////////////////////////////////// ///@brief State of the interface for communicating with a MIP device. /// typedef struct mip_interface { - mip_parser _parser; ///<@private MIP Parser for incoming MIP packets. - mip_cmd_queue _queue; ///<@private Queue for checking command replies. - mip_dispatcher _dispatcher; ///<@private Dispatcher for data callbacks. - unsigned int _max_update_pkts; ///<@private Max number of MIP packets to parse at once. - mip_update_callback _update_function; ///<@private Optional function to call during updates. - void* _user_pointer; ///<@private Optional user-specified data pointer. + mip_parser _parser; ///<@private MIP Parser for incoming MIP packets. + mip_cmd_queue _queue; ///<@private Queue for checking command replies. + mip_dispatcher _dispatcher; ///<@private Dispatcher for data callbacks. + unsigned int _max_update_pkts; ///<@private Max number of MIP packets to parse at once. + mip_send_callback _send_callback; ///<@private Optional function which is called to send raw bytes to the device. + mip_recv_callback _recv_callback; ///<@private Optional function which is called to receive raw bytes from the device. + mip_update_callback _update_callback; ///<@private Optional function to call during updates. + void* _user_pointer; ///<@private Optional user-specified data pointer. } mip_interface; -void mip_interface_init(mip_interface* device, uint8_t* parse_buffer, size_t parse_buffer_size, timeout_type parse_timeout, timeout_type base_reply_timeout); + +void mip_interface_init( + mip_interface* device, uint8_t* parse_buffer, size_t parse_buffer_size, + mip_timeout parse_timeout, mip_timeout base_reply_timeout, + mip_send_callback send, mip_recv_callback recv, + mip_update_callback update, void* user_pointer +); // // Communications // -remaining_count mip_interface_receive_bytes(mip_interface* device, const uint8_t* data, size_t length, timestamp_type timestamp); -void mip_interface_process_unparsed_packets(mip_interface* device); -bool mip_interface_update(mip_interface* device, bool blocking); -bool mip_interface_default_update(mip_interface* device, bool blocking); - bool mip_interface_send_to_device(mip_interface* device, const uint8_t* data, size_t length); +bool mip_interface_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout timeout, size_t* length_out, mip_timestamp* now); +bool mip_interface_update(mip_interface* device, mip_timeout wait_time); -bool mip_interface_parse_callback(void* device, const mip_packet* packet, timestamp_type timestamp); -void mip_interface_receive_packet(mip_interface* device, const mip_packet* packet, timestamp_type timestamp); +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); // // Commands // -enum mip_cmd_result mip_interface_wait_for_reply(mip_interface* device, const mip_pending_cmd* cmd); +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); @@ -97,66 +98,24 @@ void mip_interface_register_extractor(mip_interface* device, mip_dispatch_handle // Accessors // +void mip_interface_set_recv_function(mip_interface* device, mip_recv_callback function); +void mip_interface_set_send_function(mip_interface* device, mip_send_callback function); void mip_interface_set_update_function(mip_interface* device, mip_update_callback function); void mip_interface_set_user_pointer(mip_interface* device, void* pointer); + void mip_interface_set_max_packets_per_update(mip_interface* device, unsigned int max_packets); unsigned int mip_interface_max_packets_per_update(const mip_interface* device); -mip_update_callback mip_interface_update_function(mip_interface* device); -void* mip_interface_user_pointer(const mip_interface* device); +mip_recv_callback mip_interface_recv_function(const mip_interface* device); +mip_send_callback mip_interface_send_function(const mip_interface* device); +mip_update_callback mip_interface_update_function(const mip_interface* device); +void* mip_interface_user_pointer(const mip_interface* device); + mip_parser* mip_interface_parser(mip_interface* device); mip_cmd_queue* mip_interface_cmd_queue(mip_interface* device); ///@} ///@} -//////////////////////////////////////////////////////////////////////////////// -///@defgroup user_callbacks User callback functions [C/CPP] -/// -///@{ - -//////////////////////////////////////////////////////////////////////////////// -///@brief Receives new data from the device. Called repeatedly -/// by mip_interface_update() while waiting for command responses. -/// -///@param device The mip interface object -///@param buffer Buffer to fill with data. Should be allocated before -/// calling this function -///@param max_length Max number of bytes that can be read into the buffer. -///@param out_length Number of bytes actually read into the buffer. -///@param timestamp_out Timestamp of the data was received. -/// -///@returns true if operation should continue, or false if the device cannot be -/// updated (e.g. if the serial port is not open). -/// -///@note Except in case of error (i.e. returning false), the timestamp must be -/// set even if no data is received. This is required to allow commands -/// to time out. -/// -///@note On systems where it makes sense, this is a good place to call sleep -/// or enter a low-power state until data arrives at the port. Typically -/// this function will wait a few milliseconds before returning. -/// -///@warning Do not block indefinitely as this will stall the system beyond the -/// normal command timeout. Use a sensible timeout (i.e. 1/10th of the -/// base reply timeout) or only sleep for a minimal amount of time. -/// -extern bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, size_t* out_length, timestamp_type* timestamp_out); - - -//////////////////////////////////////////////////////////////////////////////// -///@copydoc mip_interface_send_to_device -/// -///@note This is a good place to put logging code for debugging device -/// communications at the byte level. -/// -///@note There are cases where the data will not be a MIP packet. -/// -extern bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length); - - -///@} -//////////////////////////////////////////////////////////////////////////////// - #ifdef __cplusplus } // namespace mip diff --git a/src/mip/mip_logging.c b/src/mip/mip_logging.c new file mode 100644 index 000000000..23592293a --- /dev/null +++ b/src/mip/mip_logging.c @@ -0,0 +1,80 @@ + +#include "mip_logging.h" + +#include + +//////////////////////////////////////////////////////////////////////////////// +///@brief Global logging callback. Do not access directly +mip_log_callback mip_log_callback_ = NULL; + +//////////////////////////////////////////////////////////////////////////////// +///@brief Global logging level. Do not access directly +mip_log_level mip_log_level_ = MIP_LOG_LEVEL_OFF; + +//////////////////////////////////////////////////////////////////////////////// +///@brief Global logging user data. Do not access directly +void* mip_log_user_data_ = NULL; + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initializes the logger with a callback and user data. +/// Call MIP_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 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) +{ + mip_log_callback_ = callback; + mip_log_level_ = level; + mip_log_user_data_ = user; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the currently active logging callback +/// +///@return The currently active logging callback +/// +mip_log_callback mip_logging_callback() +{ + return mip_log_callback_; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the currently active logging level +/// +///@return The currently active logging level +/// +mip_log_level mip_logging_level() +{ + return mip_log_level_; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the currently active logging user data +/// +///@return The currently active logging user data +/// +void* mip_logging_user_data() +{ + return mip_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 +/// +void mip_logging_log(mip_log_level level, const char* fmt, ...) +{ + const mip_log_callback logging_callback = mip_logging_callback(); + const mip_log_level logging_level = mip_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); + va_end(args); + } +} \ No newline at end of file diff --git a/src/mip/mip_logging.h b/src/mip/mip_logging.h new file mode 100644 index 000000000..b847b729a --- /dev/null +++ b/src/mip/mip_logging.h @@ -0,0 +1,141 @@ +#pragma once + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_c +///@{ +//////////////////////////////////////////////////////////////////////////////// +///@defgroup mip_logging Mip Logging [C] +/// +///@brief High-level C functions for logging information from within the MIP SDK +/// +/// This module contains functions that allow the MIP SDK to log information +/// and allows users to override the logging functions +/// +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@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 + +//////////////////////////////////////////////////////////////////////////////// +///@brief Callback function typedef for custom logging behavior. +/// +///@param level The log level that this log should be logged at +///@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); + +void mip_logging_init(mip_log_callback callback, mip_log_level level, void* user); + +mip_log_callback mip_logging_callback(); +mip_log_level mip_logging_level(); +void* mip_logging_user_data(); + +void mip_logging_log(mip_log_level level, const char* fmt, ...); + +//////////////////////////////////////////////////////////////////////////////// +///@brief Helper macro used to initialize the MIP 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 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) +#else +#define MIP_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::mip_log_callback +/// +#ifdef MIP_ENABLE_LOGGING +#define MIP_LOG_LOG(level, ...) mip_logging_log(level, __VA_ARGS__) +#else +#define MIP_LOG_LOG(level, ...) (void)0 +#endif + +//////////////////////////////////////////////////////////////////////////////// +///@brief Helper macro used to log data inside the MIP SDK at fatal level +/// +///@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 !defined(MIP_LOGGING_MAX_LEVEL) || 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 +#endif + +//////////////////////////////////////////////////////////////////////////////// +///@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 +#define MIP_LOG_ERROR(...) MIP_LOG_LOG(MIP_LOG_LEVEL_ERROR, __VA_ARGS__) +#else +#define MIP_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 +#if !defined(MIP_LOGGING_MAX_LEVEL) || 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 +#endif + +//////////////////////////////////////////////////////////////////////////////// +///@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 +#define MIP_LOG_INFO(...) MIP_LOG_LOG(MIP_LOG_LEVEL_INFO, __VA_ARGS__) +#else +#define MIP_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 +#if !defined(MIP_LOGGING_MAX_LEVEL) || 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 +#endif + +//////////////////////////////////////////////////////////////////////////////// +///@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 +#define MIP_LOG_TRACE(...) MIP_LOG_LOG(MIP_LOG_LEVEL_TRACE, __VA_ARGS__) +#else +#define MIP_LOG_TRACE(...) (void)0 +#endif + +///@} +///@} +//////////////////////////////////////////////////////////////////////////////// + +#ifdef __cplusplus +} // extern "C" +#endif \ No newline at end of file diff --git a/src/mip/mip_packet.c b/src/mip/mip_packet.c index 92295f403..d5f6496af 100644 --- a/src/mip/mip_packet.c +++ b/src/mip/mip_packet.c @@ -1,461 +1,465 @@ - -#include "mip_packet.h" -#include "mip_offsets.h" - -#include "definitions/descriptors.h" - -#include -#include - - -// -// Initialization -// - -//////////////////////////////////////////////////////////////////////////////// -///@brief Initializes a MIP packet from an existing buffer. -/// -/// Use this when receiving or parsing MIP packets. -/// -/// The data in the buffer should be a valid or suspected MIP packet. -/// -///@param packet -///@param buffer -/// The data buffer containing the bytes for a MIP packet. Must be at -/// least MIP_PACKET_LENGTH_MIN bytes in size. -///@param length -/// The length of the data pointed to by buffer. -/// -///@note The data does not need to be a valid MIP packet, for instance to use -/// the mip_packet_is_sane() or mip_packet_is_valid() functions. However, if -/// it is NOT a valid MIP packet, the result of calling any accessor -/// function is unpredictable. In particular, if length is less than -/// 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) -{ - assert(buffer != NULL); - - // Limit the length in case it's longer than a mip packer (or worse, longer than the buffer size field can hold) - if( length > MIP_PACKET_LENGTH_MAX ) - length = MIP_PACKET_LENGTH_MAX; - - packet->_buffer = buffer; - packet->_buffer_length = length; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Create a brand-new MIP packet in the given buffer. -/// -/// Use this along with the packet building functions to create MIP packets. -/// -///@param packet -///@param buffer -/// This is where the packet bytes will be stored. Must be at least -/// MIP_PACKET_LENGTH_MIN bytes in size. -///@param buffer_size -/// The size of buffer, in bytes. -///@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) -{ - mip_packet_from_buffer(packet, buffer, buffer_size); - - if( buffer_size < MIP_PACKET_LENGTH_MIN ) - { - assert(false); // Buffer too small! - return; - } - - packet->_buffer[MIP_INDEX_SYNC1] = MIP_SYNC1; - packet->_buffer[MIP_INDEX_SYNC2] = MIP_SYNC2; - packet->_buffer[MIP_INDEX_DESCSET] = descriptor_set; - packet->_buffer[MIP_INDEX_LENGTH] = 0; -} - - - -// -// Accessors -// - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns the MIP descriptor set for this packet. -/// -uint8_t mip_packet_descriptor_set(const mip_packet* packet) -{ - return packet->_buffer[MIP_INDEX_DESCSET]; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns the length of the payload (MIP fields). -/// -uint8_t mip_packet_payload_length(const mip_packet* packet) -{ - return packet->_buffer[MIP_INDEX_LENGTH]; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns the total length of the packet, in bytes. -/// -///@returns The length of the packet. Always at least MIP_PACKET_LENGTH_MIN. -/// -packet_length mip_packet_total_length(const mip_packet* packet) -{ - return mip_packet_payload_length(packet) + MIP_PACKET_LENGTH_MIN; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns a writable pointer to the data buffer. -/// -uint8_t* mip_packet_buffer(mip_packet* packet) -{ - return packet->_buffer; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns a pointer to the data buffer containing the packet. -/// -const uint8_t* mip_packet_pointer(const mip_packet* packet) -{ - return packet->_buffer; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns a pointer to the packet's payload (the first field). -/// -const uint8_t* mip_packet_payload(const mip_packet* packet) -{ - return packet->_buffer + MIP_INDEX_PAYLOAD; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns the value of the checksum as written in the 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) -{ - const packet_length index = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; - - return ((uint16_t)(packet->_buffer[index+0]) << 8) | (uint16_t)(packet->_buffer[index+1]); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Computes the checksum of the MIP packet. -/// -///@returns The computed checksum value. -/// -uint16_t mip_packet_compute_checksum(const mip_packet* packet) -{ - uint8_t a = 0; - uint8_t b = 0; - - // mip_packet_total_length always returns at least MIP_PACKET_LENGTH_MIN so this - // subtraction is guaranteed to be safe. - const packet_length length = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; - - for(packet_length i=0; i_buffer[i]; - b += a; - } - - return ((uint16_t)(a) << 8) | (uint16_t)(b); -} - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns true if the packet buffer is not NULL and is at least the -/// minimum size (MIP_PACKET_LENGTH_MIN). -/// -/// If the packet is not 'sane', then none of the mip_packet_* functions may be -/// 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) -{ - return packet->_buffer && (mip_packet_buffer_size(packet) >= MIP_PACKET_LENGTH_MIN); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns true if the packet is valid. -/// -/// A packet is valid if: -/// * mip_packet_is_sane() returns true, -/// * The descriptor set is not 0x00, and -/// * The checksum is valid. -/// -bool mip_packet_is_valid(const mip_packet* packet) -{ - if( !mip_packet_is_sane(packet) || (mip_packet_descriptor_set(packet) == 0x00) ) - return false; - - const uint16_t listed_checksum = mip_packet_checksum_value(packet); - const uint16_t computed_checksum = mip_packet_compute_checksum(packet); - - return listed_checksum == computed_checksum; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns true if the mip packet contains no payload. -/// -///@param packet -/// -///@returns true if the packet has a payload length of 0. -/// -bool mip_packet_is_empty(const mip_packet* packet) -{ - if( !mip_packet_is_sane(packet) ) - return true; - - return mip_packet_payload_length(packet) == 0; -} - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns the size of the buffer backing the MIP packet. -/// -///@note This is the BUFFER SIZE and not the packet length. -/// -packet_length mip_packet_buffer_size(const mip_packet* packet) -{ - return packet->_buffer_length; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns the remaining space available for more payload data. -/// -/// This is equal to the buffer size less the total packet length. -/// -remaining_count mip_packet_remaining_space(const mip_packet* packet) -{ - return mip_packet_buffer_size(packet) - mip_packet_total_length(packet); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Returns true if the packet is from a data descriptor set. -/// -///@see is_data_descriptor_set -/// -///@returns true if the packet contains data. -///@returns false if it contains commands or replies. -/// -bool mip_packet_is_data(const mip_packet* packet) -{ - return mip_is_data_descriptor_set(mip_packet_descriptor_set(packet)); -} - -// -// Packet Building -// - -//////////////////////////////////////////////////////////////////////////////// -///@brief Adds a pre-constructed MIP field to the packet. -/// -///~~~ -/// +--------------------+ -/// | Payload Bytes | -/// Len Desc +--------------------+ -/// | | | copy -/// Packet Buffer V V V -/// ---------------+------------+- -+- -+-- -+- -/// ... Header | Field | Len | Desc | Payload | -/// ---------------+------------+-----+------+---------------------+---------- -/// | | -/// End of last field ---------------> End of new field -///~~~ -/// -/// -///@param packet -///@param field_descriptor -/// The MIP field descriptor (e.g. command or data descriptor). -///@param payload -/// A pointer to the field payload data (without the header). -/// Can be NULL if payload_length is 0. -///@param payload_length -/// The length of the payload data. Must be less than or equal to -/// MIP_FIELD_PAYLOAD_LENGTH_MAX. Does not include the header. -/// -///@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) -{ - uint8_t* payload_buffer; - remaining_count remaining = mip_packet_alloc_field(packet, field_descriptor, payload_length, &payload_buffer); - if( remaining < 0 ) - return false; - - memcpy(payload_buffer, payload, payload_length); - - return true; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Allocate a MIP field within the packet and return the payload pointer. -/// -///~~~ -/// Len Desc .---> Payload ptr out -/// | | | -/// Packet Buffer V V | -/// ---------------+------------+- -+- -+---------------------+---------- -/// ... Header | Field | Len | Desc | (unwritten payload) | -/// ---------------+------------+-----+------+---------------------+---------- -/// | | -/// End of last field ---------------> End of new field -///~~~ -/// -///@param packet -///@param field_descriptor -/// The MIP field descriptor (e.g. command or data descriptor). -///@param payload_length -/// The requested length of the field payload (not including the header). -/// If the size is not known ahead of time, pass 0 and inspect the return -/// value to see how much payload data can be written. Then call -/// mip_packet_realloc_field() with the used size and same payload pointer. -///@param payload_ptr_out -/// A pointer to a pointer to the field payload. This will receive the -/// payload pointer into which data should be written. -/// -///@returns The amount of space remaining after allocating this field. If this -/// is negative, the field could not be allocated and the payload must -/// not be written. -/// -remaining_count mip_packet_alloc_field(mip_packet* 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 ); - - const remaining_count remaining = mip_packet_remaining_space(packet); - - const packet_length field_length = MIP_FIELD_HEADER_LENGTH + (packet_length)payload_length; - - *payload_ptr_out = NULL; - - if( field_length <= remaining ) - { - packet_length field_index = MIP_HEADER_LENGTH + mip_packet_payload_length(packet); - - packet->_buffer[MIP_INDEX_LENGTH] += field_length; - - packet->_buffer[field_index+MIP_INDEX_FIELD_LEN] = field_length; - packet->_buffer[field_index+MIP_INDEX_FIELD_DESC] = field_descriptor; - - *payload_ptr_out = &packet->_buffer[field_index + MIP_INDEX_FIELD_PAYLOAD]; - } - - return remaining - field_length; -} - -//////////////////////////////////////////////////////////////////////////////// -///@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 -/// 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. -/// -///@param packet -///@param payload_ptr -/// Pointer to the field payload. This must be the same value returned -/// from alloc_field and must point to the last field. -///@param new_payload_length -/// Length of payload written. Generally it is an error for this to -/// exceed the actual amount of space available in the packet. In this -/// case, the packet is left with just the empty field and the return -/// value will be negative. -/// -///@returns The space remaining in the packet after changing the field size. -/// This will be negative if the new length did not fit. -/// -remaining_count mip_packet_realloc_last_field(mip_packet* packet, uint8_t* payload_ptr, uint8_t new_payload_length) -{ - assert(payload_ptr != NULL); - assert( new_payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); - - uint8_t* field_ptr = payload_ptr - MIP_INDEX_FIELD_PAYLOAD; - const uint8_t old_field_length = field_ptr[MIP_INDEX_FIELD_LEN]; - const uint8_t new_field_length = new_payload_length + MIP_FIELD_HEADER_LENGTH; - - const remaining_count delta_length = new_field_length - old_field_length; - - remaining_count remaining = mip_packet_remaining_space(packet) + delta_length; - - if( remaining >= 0 ) - { - field_ptr[MIP_INDEX_FIELD_LEN] = new_field_length; - packet->_buffer[MIP_INDEX_LENGTH] += delta_length; - } - - return remaining; -} - -//////////////////////////////////////////////////////////////////////////////// -///@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. -/// E.g. if it turns out that there isn't enough buffer space to write the -/// payload. -/// -///@param packet -///@param payload_ptr -/// Pointer to the field payload. This must be the same value returned -/// from alloc_field and must point to the last field. -/// -///@returns The remaining space in the packet after removing the field. -/// -remaining_count mip_packet_cancel_last_field(mip_packet* packet, uint8_t* payload_ptr) -{ - assert(payload_ptr != NULL); - - uint8_t* field_ptr = payload_ptr - MIP_INDEX_FIELD_PAYLOAD; - const uint8_t old_payload_length = field_ptr[MIP_INDEX_FIELD_LEN]; - - packet->_buffer[MIP_INDEX_LENGTH] -= MIP_FIELD_HEADER_LENGTH + old_payload_length; - - return mip_packet_remaining_space(packet); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Prepares the packet for transmission by adding the checksum. -/// -/// This does not increase the total packet length since the checksum is always -/// implicitly included. -/// -///~~~ -/// Checksum -/// VVVV -/// ---------------+------------+------------+-----//-----+-- --+---- -/// ... Header | Field | Field | ... | (empty) | -/// ---------------+------------+------------+-----//-----+------------+---- -/// | | -/// End of last field | -/// Total Length -///~~~ -/// -void mip_packet_finalize(mip_packet* packet) -{ - uint16_t checksum = mip_packet_compute_checksum(packet); - packet_length length = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; - - packet->_buffer[length+0] = checksum >> 8; - packet->_buffer[length+1] = checksum & 0xFF; -} - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Reinitialize the packet with the given descriptor set. -/// -/// This clears out all of the fields but keeps the same buffer. -/// -///@param packet -///@param descriptor_set New descriptor set. -/// -void mip_packet_reset(mip_packet* packet, uint8_t descriptor_set) -{ - mip_packet_create(packet, mip_packet_buffer(packet), mip_packet_buffer_size(packet), descriptor_set); -} - + +#include "mip_packet.h" +#include "mip_offsets.h" + +#include "definitions/descriptors.h" + +#include +#include + + +// +// Initialization +// + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initializes a MIP packet from an existing buffer. +/// +/// Use this when receiving or parsing MIP packets. +/// +/// The data in the buffer should be a valid or suspected MIP packet. +/// +///@param packet +///@param buffer +/// The data buffer containing the bytes for a MIP packet. Must be at +/// least MIP_PACKET_LENGTH_MIN bytes in size. +///@param length +/// The length of the data pointed to by buffer. +/// +///@note The data does not need to be a valid MIP packet, for instance to use +/// the mip_packet_is_sane() or mip_packet_is_valid() functions. However, if +/// it is NOT a valid MIP packet, the result of calling any accessor +/// function is unpredictable. In particular, if length is less than +/// 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) +{ + assert(buffer != NULL); + + // Limit the length in case it's longer than a mip packer (or worse, longer than the buffer size field can hold) + if( length > MIP_PACKET_LENGTH_MAX ) + length = MIP_PACKET_LENGTH_MAX; + + packet->_buffer = buffer; + packet->_buffer_length = (uint_least16_t)length; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Create a brand-new MIP packet in the given buffer. +/// +/// Use this along with the packet building functions to create MIP packets. +/// +///@param packet +///@param buffer +/// This is where the packet bytes will be stored. Must be at least +/// MIP_PACKET_LENGTH_MIN bytes in size. +///@param buffer_size +/// The size of buffer, in bytes. +///@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) +{ + mip_packet_from_buffer(packet, buffer, buffer_size); + + if( buffer_size < MIP_PACKET_LENGTH_MIN ) + { + assert(false); // Buffer too small! + return; + } + + packet->_buffer[MIP_INDEX_SYNC1] = MIP_SYNC1; + packet->_buffer[MIP_INDEX_SYNC2] = MIP_SYNC2; + packet->_buffer[MIP_INDEX_DESCSET] = descriptor_set; + packet->_buffer[MIP_INDEX_LENGTH] = 0; +} + + + +// +// Accessors +// + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the MIP descriptor set for this packet. +/// +uint8_t mip_packet_descriptor_set(const mip_packet* packet) +{ + return packet->_buffer[MIP_INDEX_DESCSET]; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the length of the payload (MIP fields). +/// +uint8_t mip_packet_payload_length(const mip_packet* packet) +{ + return packet->_buffer[MIP_INDEX_LENGTH]; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the total length of the packet, in bytes. +/// +///@returns The length of the packet. Always at least MIP_PACKET_LENGTH_MIN. +/// +uint_least16_t mip_packet_total_length(const mip_packet* packet) +{ + return mip_packet_payload_length(packet) + MIP_PACKET_LENGTH_MIN; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns a writable pointer to the data buffer. +/// +uint8_t* mip_packet_buffer(mip_packet* packet) +{ + return packet->_buffer; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns a pointer to the data buffer containing the packet. +/// +const uint8_t* mip_packet_pointer(const mip_packet* packet) +{ + return packet->_buffer; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns a pointer to the packet's payload (the first field). +/// +const uint8_t* mip_packet_payload(const mip_packet* packet) +{ + return packet->_buffer + MIP_INDEX_PAYLOAD; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the value of the checksum as written in the 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) +{ + const uint_least16_t index = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; + + return ((uint16_t)(packet->_buffer[index+0]) << 8) | (uint16_t)(packet->_buffer[index+1]); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Computes the checksum of the MIP packet. +/// +///@returns The computed checksum value. +/// +uint16_t mip_packet_compute_checksum(const mip_packet* packet) +{ + uint8_t a = 0; + uint8_t b = 0; + + // mip_packet_total_length always returns at least MIP_PACKET_LENGTH_MIN so this + // subtraction is guaranteed to be safe. + const uint_least16_t length = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; + + for(uint_least16_t i=0; i_buffer[i]; + b += a; + } + + return ((uint16_t)(a) << 8) | (uint16_t)(b); +} + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns true if the packet buffer is not NULL and is at least the +/// minimum size (MIP_PACKET_LENGTH_MIN). +/// +/// If the packet is not 'sane', then none of the mip_packet_* functions may be +/// 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) +{ + return packet->_buffer && (packet->_buffer_length >= MIP_PACKET_LENGTH_MIN) && (packet->_buffer_length >= mip_packet_payload_length(packet)+MIP_PACKET_LENGTH_MIN); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns true if the packet is valid. +/// +/// A packet is valid if: +/// * mip_packet_is_sane() returns true, +/// * The descriptor set is not 0x00, and +/// * The checksum is valid. +/// +bool mip_packet_is_valid(const mip_packet* packet) +{ + if( !mip_packet_is_sane(packet) || (mip_packet_descriptor_set(packet) == 0x00) ) + return false; + + const uint16_t listed_checksum = mip_packet_checksum_value(packet); + const uint16_t computed_checksum = mip_packet_compute_checksum(packet); + + return listed_checksum == computed_checksum; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns true if the mip packet contains no payload. +/// +///@param packet +/// +///@returns true if the packet has a payload length of 0. +/// +bool mip_packet_is_empty(const mip_packet* packet) +{ + if( !mip_packet_is_sane(packet) ) + return true; + + return mip_packet_payload_length(packet) == 0; +} + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the size of the buffer backing the MIP packet. +/// +///@note This is the BUFFER SIZE and not the packet length. +/// +uint_least16_t mip_packet_buffer_size(const mip_packet* packet) +{ + return packet->_buffer_length; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns the remaining space available for more payload data. +/// +/// This is equal to the buffer size less the total packet length. +/// +///@warning The result may be negative if the packet length exceeds the actual +/// 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) +{ + return mip_packet_buffer_size(packet) - mip_packet_total_length(packet); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Returns true if the packet is from a data descriptor set. +/// +///@see is_data_descriptor_set +/// +///@returns true if the packet contains data. +///@returns false if it contains commands or replies. +/// +bool mip_packet_is_data(const mip_packet* packet) +{ + return mip_is_data_descriptor_set(mip_packet_descriptor_set(packet)); +} + +// +// Packet Building +// + +//////////////////////////////////////////////////////////////////////////////// +///@brief Adds a pre-constructed MIP field to the packet. +/// +///~~~ +/// +--------------------+ +/// | Payload Bytes | +/// Len Desc +--------------------+ +/// | | | copy +/// Packet Buffer V V V +/// ---------------+------------+- -+- -+-- -+- +/// ... Header | Field | Len | Desc | Payload | +/// ---------------+------------+-----+------+---------------------+---------- +/// | | +/// End of last field ---------------> End of new field +///~~~ +/// +/// +///@param packet +///@param field_descriptor +/// The MIP field descriptor (e.g. command or data descriptor). +///@param payload +/// A pointer to the field payload data (without the header). +/// Can be NULL if payload_length is 0. +///@param payload_length +/// The length of the payload data. Must be less than or equal to +/// MIP_FIELD_PAYLOAD_LENGTH_MAX. Does not include the header. +/// +///@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) +{ + uint8_t* payload_buffer; + int remaining = mip_packet_alloc_field(packet, field_descriptor, payload_length, &payload_buffer); + if( remaining < 0 ) + return false; + + memcpy(payload_buffer, payload, payload_length); + + return true; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Allocate a MIP field within the packet and return the payload pointer. +/// +///~~~ +/// Len Desc .---> Payload ptr out +/// | | | +/// Packet Buffer V V | +/// ---------------+------------+- -+- -+---------------------+---------- +/// ... Header | Field | Len | Desc | (unwritten payload) | +/// ---------------+------------+-----+------+---------------------+---------- +/// | | +/// End of last field ---------------> End of new field +///~~~ +/// +///@param packet +///@param field_descriptor +/// The MIP field descriptor (e.g. command or data descriptor). +///@param payload_length +/// The requested length of the field payload (not including the header). +/// If the size is not known ahead of time, pass 0 and inspect the return +/// value to see how much payload data can be written. Then call +/// mip_packet_realloc_field() with the used size and same payload pointer. +///@param payload_ptr_out +/// A pointer to a pointer to the field payload. This will receive the +/// payload pointer into which data should be written. +/// +///@returns The amount of space remaining after allocating this field. If this +/// 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) +{ + assert(payload_ptr_out != NULL); + assert( payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); + + const int remaining = mip_packet_remaining_space(packet); + + const uint8_t field_length = MIP_FIELD_HEADER_LENGTH + payload_length; + + *payload_ptr_out = NULL; + + if( field_length <= remaining ) + { + const uint_least16_t field_index = MIP_HEADER_LENGTH + mip_packet_payload_length(packet); + + packet->_buffer[MIP_INDEX_LENGTH] += field_length; + + packet->_buffer[field_index+MIP_INDEX_FIELD_LEN] = field_length; + packet->_buffer[field_index+MIP_INDEX_FIELD_DESC] = field_descriptor; + + *payload_ptr_out = &packet->_buffer[field_index + MIP_INDEX_FIELD_PAYLOAD]; + } + + return remaining - field_length; +} + +//////////////////////////////////////////////////////////////////////////////// +///@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 +/// 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. +/// +///@param packet +///@param payload_ptr +/// Pointer to the field payload. This must be the same value returned +/// from alloc_field and must point to the last field. +///@param new_payload_length +/// Length of payload written. Generally it is an error for this to +/// exceed the actual amount of space available in the packet. In this +/// case, the packet is left with just the empty field and the return +/// value will be negative. +/// +///@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) +{ + assert(payload_ptr != NULL); + assert( new_payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); + + uint8_t* field_ptr = payload_ptr - MIP_INDEX_FIELD_PAYLOAD; + const uint8_t old_field_length = field_ptr[MIP_INDEX_FIELD_LEN]; + const uint8_t new_field_length = new_payload_length + MIP_FIELD_HEADER_LENGTH; + + const int delta_length = new_field_length - old_field_length; + + const int remaining = mip_packet_remaining_space(packet) - delta_length; + + if( remaining >= 0 ) + { + field_ptr[MIP_INDEX_FIELD_LEN] = new_field_length; + packet->_buffer[MIP_INDEX_LENGTH] += (int8_t)delta_length; + } + + return remaining; +} + +//////////////////////////////////////////////////////////////////////////////// +///@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. +/// E.g. if it turns out that there isn't enough buffer space to write the +/// payload. +/// +///@param packet +///@param payload_ptr +/// Pointer to the field payload. This must be the same value returned +/// from alloc_field and must point to the last field. +/// +///@returns The remaining space in the packet after removing the field. +/// +int mip_packet_cancel_last_field(mip_packet* packet, uint8_t* payload_ptr) +{ + assert(payload_ptr != NULL); + + uint8_t* field_ptr = payload_ptr - MIP_INDEX_FIELD_PAYLOAD; + const uint8_t old_field_length = field_ptr[MIP_INDEX_FIELD_LEN]; + + packet->_buffer[MIP_INDEX_LENGTH] -= old_field_length; + + return mip_packet_remaining_space(packet); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Prepares the packet for transmission by adding the checksum. +/// +/// This does not increase the total packet length since the checksum is always +/// implicitly included. +/// +///~~~ +/// Checksum +/// VVVV +/// ---------------+------------+------------+-----//-----+-- --+---- +/// ... Header | Field | Field | ... | (empty) | +/// ---------------+------------+------------+-----//-----+------------+---- +/// | | +/// End of last field | +/// Total Length +///~~~ +/// +void mip_packet_finalize(mip_packet* packet) +{ + uint16_t checksum = mip_packet_compute_checksum(packet); + uint_least16_t length = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; + + packet->_buffer[length+0] = checksum >> 8; + packet->_buffer[length+1] = checksum & 0xFF; +} + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Reinitialize the packet with the given descriptor set. +/// +/// This clears out all of the fields but keeps the same buffer. +/// +///@param packet +///@param descriptor_set New descriptor set. +/// +void mip_packet_reset(mip_packet* 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 0f22d98e6..e98287fcb 100644 --- a/src/mip/mip_packet.h +++ b/src/mip/mip_packet.h @@ -29,8 +29,6 @@ extern "C" { ///@{ -typedef uint_least16_t packet_length; ///< Type used for the length of a MIP packet. - //////////////////////////////////////////////////////////////////////////////// ///@brief Structure representing a MIP Packet. /// @@ -42,7 +40,7 @@ typedef uint_least16_t packet_length; ///< Type used for the length of a MIP pa /// typedef struct mip_packet { - uint8_t* _buffer; ///<@private Pointer to the packet data. + 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; @@ -59,10 +57,10 @@ typedef struct mip_packet void mip_packet_create(mip_packet* 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); -remaining_count mip_packet_alloc_field(mip_packet* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** payload_ptr_out); -remaining_count mip_packet_realloc_last_field(mip_packet* packet, uint8_t* payload_ptr, uint8_t new_payload_length); -remaining_count mip_packet_cancel_last_field(mip_packet* packet, uint8_t* payload_ptr); +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); void mip_packet_finalize(mip_packet* packet); @@ -85,7 +83,7 @@ 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); uint8_t mip_packet_descriptor_set(const mip_packet* packet); -packet_length mip_packet_total_length(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); @@ -98,8 +96,8 @@ 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); -packet_length mip_packet_buffer_size(const mip_packet* packet); -remaining_count mip_packet_remaining_space(const mip_packet* packet); +uint_least16_t mip_packet_buffer_size(const mip_packet* packet); +int mip_packet_remaining_space(const mip_packet* packet); bool mip_packet_is_data(const mip_packet* packet); diff --git a/src/mip/mip_parser.c b/src/mip/mip_parser.c index dc4889c67..d6192347e 100644 --- a/src/mip/mip_parser.c +++ b/src/mip/mip_parser.c @@ -29,16 +29,13 @@ /// The timeout for receiving one packet. Depends on the serial baud rate /// and is typically 100 milliseconds. /// -void mip_parser_init(mip_parser* parser, uint8_t* buffer, size_t buffer_size, mip_packet_callback callback, void* callback_object, timestamp_type timeout) +void mip_parser_init(mip_parser* parser, uint8_t* buffer, size_t buffer_size, mip_packet_callback callback, void* callback_object, mip_timestamp timeout) { - parser->_start_time = 0; - parser->_timeout = timeout; - - parser->_result_buffer[0] = 0; - byte_ring_init(&parser->_ring, buffer, buffer_size); - parser->_expected_length = MIPPARSER_RESET_LENGTH; + parser->_timeout = timeout; + + mip_parser_reset(parser); parser->_callback = callback; parser->_callback_object = callback_object; @@ -59,6 +56,13 @@ void mip_parser_reset(mip_parser* parser) parser->_result_buffer[0] = 0; parser->_start_time = 0; byte_ring_clear(&parser->_ring); + + MIP_DIAG_ZERO(parser->_diag_bytes_read); + MIP_DIAG_ZERO(parser->_diag_bytes_skipped); + MIP_DIAG_ZERO(parser->_diag_packet_bytes); + MIP_DIAG_ZERO(parser->_diag_valid_packets); + MIP_DIAG_ZERO(parser->_diag_invalid_packets); + MIP_DIAG_ZERO(parser->_diag_timeouts); } //////////////////////////////////////////////////////////////////////////////// @@ -108,21 +112,29 @@ void mip_parser_reset(mip_parser* parser) /// conntains 0x75,0x65, has at least 6 bytes, and has a valid checksum. A /// 16-bit checksum has a 1 in 65,536 chance of appearing to be valid. /// -remaining_count mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t input_count, timestamp_type timestamp, unsigned int max_packets) +size_t mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t input_count, mip_timestamp timestamp, unsigned int max_packets) { // Reset the state if the timeout time has elapsed. if( parser->_expected_length != MIPPARSER_RESET_LENGTH && (timestamp - parser->_start_time) > parser->_timeout ) { if( byte_ring_count(&parser->_ring) > 0 ) + { byte_ring_pop(&parser->_ring, 1); + MIP_DIAG_INC(parser->_diag_bytes_skipped, 1); + } + parser->_expected_length = MIPPARSER_RESET_LENGTH; + + MIP_DIAG_INC(parser->_diag_timeouts, 1); } unsigned int num_packets = 0; do { // Copy as much data as will fit in the ring buffer. - byte_ring_copy_from_and_update(&parser->_ring, &input_buffer, &input_count); + size_t count = byte_ring_copy_from_and_update(&parser->_ring, &input_buffer, &input_count); + + MIP_DIAG_INC(parser->_diag_bytes_read, count); mip_packet packet; while( mip_parser_parse_one_packet_from_ring(parser, &packet, timestamp) ) @@ -136,9 +148,11 @@ remaining_count mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer if( stop ) { // Pull more data from the input buffer if possible. - byte_ring_copy_from_and_update(&parser->_ring, &input_buffer, &input_count); + count = byte_ring_copy_from_and_update(&parser->_ring, &input_buffer, &input_count); + + MIP_DIAG_INC(parser->_diag_bytes_read, count); - return -(remaining_count)input_count; + return input_count; } } @@ -148,7 +162,7 @@ remaining_count mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer } while( input_count ); - return -(remaining_count)input_count; + return input_count; } //////////////////////////////////////////////////////////////////////////////// @@ -165,7 +179,7 @@ remaining_count mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer ///@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, timestamp_type timestamp) +bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* 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 ) @@ -173,7 +187,11 @@ bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packe if( parser->_expected_length == MIPPARSER_RESET_LENGTH ) { if( byte_ring_at(&parser->_ring, MIP_INDEX_SYNC1) != MIP_SYNC1 ) + { byte_ring_pop(&parser->_ring, 1); + + MIP_DIAG_INC(parser->_diag_bytes_skipped, 1); + } else { // Synchronized - set the start time and expect more data. @@ -187,6 +205,7 @@ bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packe if( byte_ring_at(&parser->_ring, MIP_INDEX_SYNC2) != MIP_SYNC2 ) { byte_ring_pop(&parser->_ring, 1); + MIP_DIAG_INC(parser->_diag_bytes_skipped, 1); parser->_expected_length = MIPPARSER_RESET_LENGTH; } else @@ -200,7 +219,7 @@ bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packe uint_least16_t packet_length = parser->_expected_length; parser->_expected_length = MIPPARSER_RESET_LENGTH; // Reset parsing state - byte_ring_copy_to(&parser->_ring, parser->_result_buffer, packet_length); + byte_ring_copy_to(&parser->_ring, parser->_result_buffer, packet_length); mip_packet_from_buffer(packet_out, parser->_result_buffer, packet_length); @@ -208,12 +227,17 @@ bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packe { // Invalid packet, drop just the first sync byte and restart. byte_ring_pop(&parser->_ring, 1); + MIP_DIAG_INC(parser->_diag_bytes_skipped, 1); + MIP_DIAG_INC(parser->_diag_invalid_packets, 1); } else // Checksum is valid { // Discard the packet bytes from the ring buffer since a copy was made. byte_ring_pop(&parser->_ring, packet_length); + MIP_DIAG_INC(parser->_diag_valid_packets, 1); + MIP_DIAG_INC(parser->_diag_packet_bytes, packet_length); + // Successfully parsed a packet. return true; } @@ -230,7 +254,7 @@ bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packe ///@brief Returns the packet timeout of the parser. /// /// -timestamp_type mip_parser_timeout(const mip_parser* parser) +mip_timestamp mip_parser_timeout(const mip_parser* parser) { return parser->_timeout; } @@ -242,7 +266,7 @@ timestamp_type mip_parser_timeout(const mip_parser* parser) ///@param parser ///@param timeout /// -void mip_parser_set_timeout(mip_parser* parser, timestamp_type timeout) +void mip_parser_set_timeout(mip_parser* parser, mip_timestamp timeout) { parser->_timeout = timeout; } @@ -303,7 +327,7 @@ void* mip_parser_callback_object(const mip_parser* parser) /// won't matter because an additional call to parse won't produce a new /// packet to be timestamped. /// -timestamp_type mip_parser_last_packet_timestamp(const mip_parser* parser) +mip_timestamp mip_parser_last_packet_timestamp(const mip_parser* parser) { return parser->_start_time; } @@ -354,13 +378,88 @@ size_t mip_parser_get_write_ptr(mip_parser* parser, uint8_t** const ptr_out) ///@param timestamp ///@param max_packets /// -void mip_parser_process_written(mip_parser* parser, size_t count, timestamp_type timestamp, unsigned int max_packets) +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); + byte_ring_notify_written(&parser->_ring, count); mip_parser_parse(parser, NULL, 0, timestamp, max_packets); } +#ifdef MIP_ENABLE_DIAGNOSTICS + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the total number of bytes read from the user input buffer. +/// +/// This includes data read into the internal ring buffer but not yet seen by +/// the parser. Ensure all packets have been processed by the parser before +/// comparing against the packet_bytes counter. +/// +uint32_t mip_parser_diagnostic_bytes_read(const mip_parser* parser) +{ + return parser->_diag_bytes_read; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets total the number of bytes that have been parsed into valid +/// packets. +/// +/// This is a summation of the total length of every valid mip packet emitted by +/// the parser. +/// +uint32_t mip_parser_diagnostic_packet_bytes(const mip_parser* parser) +{ + return parser->_diag_packet_bytes; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the total number of bytes which weren't part of a valid packet. +/// +/// This is the difference between the "packet bytes" and "bytes read" counters. +/// +uint32_t mip_parser_diagnostic_bytes_skipped(const mip_parser* parser) +{ + return parser->_diag_bytes_skipped; +} + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the total number of valid packets emitted by the parser. +/// +uint32_t mip_parser_diagnostic_valid_packets(const mip_parser* parser) +{ + return parser->_diag_valid_packets; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the total number of packets that failed the checksum check. +/// +/// These invalid packets are not emitted by the parser and are not included in +/// the "valid packets" or "packet bytes" counters. +/// +uint32_t mip_parser_diagnostic_invalid_packets(const mip_parser* parser) +{ + return parser->_diag_invalid_packets; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Gets the total number of times a packet timed out waiting for more +/// data. +/// +/// Packets may time out under the following conditions: +///@li The connection is interrupted +///@li The length byte is corrupted to make the packet look longer +///@li The connection bandwidth and/or latency is too low +/// +uint32_t mip_parser_diagnostic_timeouts(const mip_parser* parser) +{ + return parser->_diag_timeouts; +} + +#endif // MIP_ENABLE_DIAGNOSTICS + + //////////////////////////////////////////////////////////////////////////////// ///@brief Computes an appropriate packet timeout for a given serial baud rate. /// @@ -373,7 +472,7 @@ void mip_parser_process_written(mip_parser* parser, size_t count, timestamp_type /// a single mip packet of maximum size at the given baud rate, plus some /// tolerance. /// -timeout_type mip_timeout_from_baudrate(uint32_t baudrate) +mip_timeout mip_timeout_from_baudrate(uint32_t baudrate) { // num_symbols [b] = (packet_length [B]) * (10 [b/B]) unsigned int num_symbols = MIP_PACKET_LENGTH_MAX * 10; diff --git a/src/mip/mip_parser.h b/src/mip/mip_parser.h index 29fa20d36..059b38043 100644 --- a/src/mip/mip_parser.h +++ b/src/mip/mip_parser.h @@ -40,9 +40,9 @@ extern "C" { ///@brief Callback function which receives parsed MIP packets. ///@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 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, timestamp_type timestamp); +typedef bool (*mip_packet_callback)(void* user, const mip_packet* packet, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// @@ -54,13 +54,23 @@ typedef bool (*mip_packet_callback)(void* user, const mip_packet* packet, timest /// typedef struct mip_parser { - timestamp_type _start_time; ///<@private The timestamp when the first byte was observed by the parser. - timestamp_type _timeout; ///<@private Duration to wait for the rest of the data in a packet. + mip_timestamp _start_time; ///<@private The timestamp when the first byte was observed by the parser. + mip_timestamp _timeout; ///<@private Duration to wait for the rest of the data in a packet. uint8_t _result_buffer[MIP_PACKET_LENGTH_MAX]; ///<@private Buffer used to output MIP packets to the callback. - packet_length _expected_length; ///<@private Expected length of the packet currently being parsed. Keeps track of parser state. Always 1, MIP_HEADER_LENGTH, or at least MIP_PACKET_LENGTH_MAX. + uint16_t _expected_length; ///<@private Expected length of the packet currently being parsed. Keeps track of parser state. Always 1, MIP_HEADER_LENGTH, or at least MIP_PACKET_LENGTH_MAX. byte_ring_state _ring; ///<@private Ring buffer which holds data being parsed. User-specified backing buffer and size. mip_packet_callback _callback; ///<@private Callback called when a valid packet is parsed. Can be NULL. void* _callback_object; ///<@private User-specified pointer passed to the callback function. + +#ifdef MIP_ENABLE_DIAGNOSTICS + uint32_t _diag_bytes_read; ///<@private Counts bytes read from the user input buffer. + uint32_t _diag_bytes_skipped; ///<@private Counts bytes read from the user input buffer. + uint32_t _diag_packet_bytes; ///<@private Counts bytes parsed into valid packets. + uint32_t _diag_valid_packets; ///<@private Counts packets successfully parsed. + uint32_t _diag_invalid_packets; ///<@private Counts invalid packets encountered (bad checksums). + uint32_t _diag_timeouts; ///<@private Counts packet timeouts. +#endif // MIP_ENABLE_DIAGNOSTICS + } mip_parser; @@ -69,33 +79,51 @@ typedef struct mip_parser #define MIPPARSER_DEFAULT_TIMEOUT_MS 100 ///< Specifies the default timeout for a MIP parser, assuming timestamps are in milliseconds. -void mip_parser_init(mip_parser* parser, uint8_t* buffer, size_t buffer_size, mip_packet_callback callback, void* callback_object, timestamp_type timeout); -bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packet_out, timestamp_type timestamp); -remaining_count mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t input_count, timestamp_type timestamp, unsigned int max_packets); +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); +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); size_t mip_parser_get_write_ptr(mip_parser* parser, uint8_t** ptr_out); -void mip_parser_process_written(mip_parser* parser, size_t count, timestamp_type timestamp, unsigned int max_packets); +void mip_parser_process_written(mip_parser* parser, size_t count, mip_timestamp timestamp, unsigned int max_packets); // // Accessors // -timeout_type mip_parser_timeout(const mip_parser* parser); -void mip_parser_set_timeout(mip_parser* parser, timeout_type timeout); +mip_timeout mip_parser_timeout(const mip_parser* parser); +void mip_parser_set_timeout(mip_parser* parser, mip_timeout timeout); void mip_parser_set_callback(mip_parser* parser, mip_packet_callback callback, void* callback_object); mip_packet_callback mip_parser_callback(const mip_parser* parser); void* mip_parser_callback_object(const mip_parser* parser); -timestamp_type mip_parser_last_packet_timestamp(const mip_parser* parser); +mip_timestamp mip_parser_last_packet_timestamp(const mip_parser* parser); + + +// +// Diagnostics +// + +#ifdef MIP_ENABLE_DIAGNOSTICS + +uint32_t mip_parser_diagnostic_bytes_read(const mip_parser* parser); +uint32_t mip_parser_diagnostic_bytes_skipped(const mip_parser* parser); +uint32_t mip_parser_diagnostic_packet_bytes(const mip_parser* parser); + +uint32_t mip_parser_diagnostic_valid_packets(const mip_parser* parser); +uint32_t mip_parser_diagnostic_invalid_packets(const mip_parser* parser); +uint32_t mip_parser_diagnostic_timeouts(const mip_parser* parser); + +#endif // MIP_ENABLE_DIAGNOSTICS + // // Misc // -timeout_type mip_timeout_from_baudrate(uint32_t baudrate); +mip_timeout mip_timeout_from_baudrate(uint32_t baudrate); ///@} ///@} diff --git a/src/mip/mip_result.c b/src/mip/mip_result.c index 12ca8c9df..e8c08e438 100644 --- a/src/mip/mip_result.c +++ b/src/mip/mip_result.c @@ -32,7 +32,9 @@ 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"; - default: return ""; + default: + if(mip_cmd_result_is_user(result)) return "User Status"; + else return "Unknown"; } } @@ -61,6 +63,14 @@ bool mip_cmd_result_is_status(enum mip_cmd_result result) return result < 0; } +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the result code was generated by user software. +/// +bool mip_cmd_result_is_user(enum mip_cmd_result result) +{ + return result <= MIP_STATUS_USER_START; +} + //////////////////////////////////////////////////////////////////////////////// ///@brief Determines if the result is an ack (successful response from the device) /// diff --git a/src/mip/mip_result.h b/src/mip/mip_result.h index a09f6be70..c08dce000 100644 --- a/src/mip/mip_result.h +++ b/src/mip/mip_result.h @@ -19,16 +19,22 @@ extern "C" { /// /// Values that start with MIP_STATUS are status codes from this library. /// Values that start with MIP_(N)ACK represent replies from the device. +/// Values at or below MIP_STATUS_USER_START (negative values) are reserved for +/// status codes from user code. /// typedef enum mip_cmd_result { - 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_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. + + // Device replies >= 0 MIP_ACK_OK = 0x00, ///< Command completed successfully. MIP_NACK_COMMAND_UNKNOWN = 0x01, ///< Command not supported. MIP_NACK_INVALID_CHECKSUM = 0x02, ///< Reserved. @@ -43,6 +49,7 @@ bool mip_cmd_result_is_finished(enum mip_cmd_result result); bool mip_cmd_result_is_reply(enum mip_cmd_result result); bool mip_cmd_result_is_status(enum mip_cmd_result result); +bool mip_cmd_result_is_user(enum mip_cmd_result result); bool mip_cmd_result_is_ack(enum mip_cmd_result result); @@ -53,18 +60,25 @@ bool mip_cmd_result_is_ack(enum mip_cmd_result result); } // extern "C" } // namespace C +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ + //////////////////////////////////////////////////////////////////////////////// ///@brief Represents the status of a MIP command. /// -/// This is the same as the mip_cmd_result C enum, but with member functions -/// and some operator overloads. +/// 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 @@ -85,22 +99,24 @@ struct CmdResult C::mip_cmd_result value = C::MIP_STATUS_NONE; - CmdResult() : value(C::MIP_ACK_OK) {} - CmdResult(C::mip_cmd_result result) : value(result) {} + 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 CmdResult fromAckNack(uint8_t code) { return CmdResult(static_cast(code)); } + 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(); } - bool operator==(CmdResult other) const { return value == other.value; } - bool operator!=(CmdResult other) const { return value != other.value; } + constexpr bool operator==(CmdResult other) const { return value == other.value; } + constexpr bool operator!=(CmdResult other) const { return value != other.value; } - bool operator==(C::mip_cmd_result other) const { return value == other; } - bool operator!=(C::mip_cmd_result other) const { return value != other; } + 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); } diff --git a/src/mip/mip_types.h b/src/mip/mip_types.h index a32b6def8..3fb409544 100644 --- a/src/mip/mip_types.h +++ b/src/mip/mip_types.h @@ -12,10 +12,6 @@ extern "C" { -// Used like a signed version of size_t -typedef int_least16_t remaining_count; - - ///@brief Type used for packet timestamps and timeouts. /// /// Timestamps must be monotonic except for overflow at the maximum value back to 0. @@ -26,22 +22,39 @@ typedef int_least16_t remaining_count; /// this requirement may result in false timeouts or delays in getting parsed packets. /// #ifdef MIP_TIMESTAMP_TYPE - typedef MIP_TIMESTAMP_TYPE timestamp_type; - static_assert( sizeof(timestamp_type) >= 8 || timestamp_type(-1) > 0, "MIP_TIMESTAMP_TYPE must be unsigned unless 64 bits."); + 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."); #else - typedef uint64_t timestamp_type; + typedef uint64_t mip_timestamp; #endif -typedef timestamp_type timeout_type; +typedef mip_timestamp mip_timeout; + + +#ifdef MIP_ENABLE_DIAGNOSTICS + +// Saturating addition +#define MIP_DIAG_INC(counter, amount) do { if (counter + amount < counter) counter = -1; else counter += amount; } while(false) + +#define MIP_DIAG_ZERO(counter) counter = 0 + +#else // MIP_ENABLE_DIAGNOSTICS + +// Do nothing if diagnostic counters diabled. Cast amount to void to avoid "unused local variable" warnings. +#define MIP_DIAG_INC(counter, amount) (void)amount + +#define MIP_DIAG_ZERO(counter) (void)0 + +#endif // MIP_ENABLE_DIAGNOSTICS + #ifdef __cplusplus } // extern "C" } // namespace C -using RemainingCount = C::remaining_count; -using Timestamp = C::timestamp_type; -using Timeout = C::timeout_type; +using Timestamp = C::mip_timestamp; +using Timeout = C::mip_timeout; } // namespace mip diff --git a/src/mip/platform/serial_connection.cpp b/src/mip/platform/serial_connection.cpp index e3d759b36..22603e7a6 100644 --- a/src/mip/platform/serial_connection.cpp +++ b/src/mip/platform/serial_connection.cpp @@ -9,28 +9,65 @@ namespace mip namespace platform { +///@brief Creates a SerialConnection 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 SerialConnection::SerialConnection(const std::string& portName, uint32_t baudrate) { - if (!serial_port_open(&mPort, portName.c_str(), baudrate)) - throw std::runtime_error("Unable to open serial port"); + mPortName = portName; + mBaudrate = baudrate; + mType = TYPE; + + serial_port_init(&mPort); } +///@brief Closes the underlying serial port SerialConnection::~SerialConnection() { - serial_port_close(&mPort); + SerialConnection::disconnect(); +} + +///@brief Check if the port is connected +bool SerialConnection::isConnected() const +{ + return serial_port_is_open(&mPort); +} + +///@brief Connect to the port +bool SerialConnection::connect() +{ + if (serial_port_is_open(&mPort)) + return true; + + return serial_port_open(&mPort, mPortName.c_str(), mBaudrate); } -bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, size_t* length_out, mip::Timestamp* timestamp) +///@brief Disconnect from the port +bool SerialConnection::disconnect() { - *timestamp = getCurrentTimestamp(); - return serial_port_read(&mPort, buffer, max_length, length_out); + if (!serial_port_is_open(&mPort)) + return true; + + return serial_port_close(&mPort); +} + + + +///@copydoc mip::Connection::recvFromDevice +bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) +{ + *timestamp = 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); } +///@copydoc mip::Connection::sendToDevice bool SerialConnection::sendToDevice(const uint8_t* data, size_t length) { size_t length_out; return serial_port_write(&mPort, data, length, &length_out); } -}; // namespace platform -}; // namespace mip \ No newline at end of file +} // namespace platform +} // namespace mip diff --git a/src/mip/platform/serial_connection.hpp b/src/mip/platform/serial_connection.hpp index 6aed1a30a..6ecd6d5f1 100644 --- a/src/mip/platform/serial_connection.hpp +++ b/src/mip/platform/serial_connection.hpp @@ -5,27 +5,63 @@ #include - -extern mip::Timestamp getCurrentTimestamp(); - namespace mip { namespace platform { +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_platform +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief Can be used on Windows, OSX, or linux to communicate with a MIP device over serial +/// class SerialConnection : public mip::Connection { public: - SerialConnection() = default; + + static constexpr auto TYPE = "Serial"; + SerialConnection(const std::string& portName, uint32_t baudrate); ~SerialConnection(); - bool recvFromDevice(uint8_t* buffer, size_t max_length, size_t* length_out, mip::Timestamp* timestamp) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) final; bool sendToDevice(const uint8_t* data, size_t length) final; + bool isConnected() const override; + bool connect() override; + bool disconnect() override; + + void connectionInfo(std::string &name, uint32_t &baudrate) const + { + name = mPortName; + baudrate = mBaudrate; + }; + private: serial_port mPort; + std::string mPortName; + uint32_t mBaudrate; + +public: + const char* interfaceName() const override { return mPortName.c_str(); } + uint32_t parameter() const override { return mBaudrate; } +}; + + +//////////////////////////////////////////////////////////////////////////////// +///@brief A serial connection but indicates that it's actually a USB connection. +class UsbSerialConnection : public SerialConnection +{ +public: + static constexpr auto TYPE = "USB"; + + UsbSerialConnection(const std::string& portName, uint32_t baudrate) : SerialConnection(portName, baudrate) { mType = TYPE; } }; -}; // namespace platform -}; // namespace mip \ No newline at end of file +///@} +//////////////////////////////////////////////////////////////////////////////// + +} // namespace platform +} // namespace mip \ No newline at end of file diff --git a/src/mip/platform/tcp_connection.cpp b/src/mip/platform/tcp_connection.cpp index a3fb21bf4..8131a465c 100644 --- a/src/mip/platform/tcp_connection.cpp +++ b/src/mip/platform/tcp_connection.cpp @@ -10,28 +10,67 @@ namespace mip namespace platform { +///@brief Creates a TcpConnection that will communicate with a device over TCP +/// +///@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) { - if (!tcp_socket_open(&mSocket, hostname.c_str(), port, 3000)) - throw std::runtime_error("Unable to open TCP socket"); + mHostname = hostname; + mPort = port; + mType = TYPE; + + tcp_socket_init(&mSocket); } +///@brief Closes the underlying TCP socket TcpConnection::~TcpConnection() { - tcp_socket_close(&mSocket); + if(isConnected()) + TcpConnection::disconnect(); +} + +///@brief Check if the socket is connected +bool TcpConnection::isConnected() const +{ + return tcp_socket_is_open(&mSocket); } -bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, size_t* length_out, mip::Timestamp* timestamp) +///@brief Connect to the socket +bool TcpConnection::connect() { - *timestamp = getCurrentTimestamp(); + if(isConnected()) + return true; + + return tcp_socket_open(&mSocket, mHostname.c_str(), mPort, 3000); +} + + +///@brief Disconnect from the socket +bool TcpConnection::disconnect() +{ + if(!isConnected()) + return true; + + return tcp_socket_close(&mSocket); +} + +///@copydoc mip::Connection::sendToDevice +bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) +{ + (void)wait_time; // Not used, timeout is always fixed + + *timestamp = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); + return tcp_socket_recv(&mSocket, buffer, max_length, length_out); } +///@copydoc mip::Connection::recvFromDevice bool TcpConnection::sendToDevice(const uint8_t* data, size_t length) { size_t length_out; return tcp_socket_send(&mSocket, data, length, &length_out); } -}; // namespace platform -}; // namespace mip \ No newline at end of file +} // namespace platform +} // namespace mip \ No newline at end of file diff --git a/src/mip/platform/tcp_connection.hpp b/src/mip/platform/tcp_connection.hpp index 9c44d384b..a33bc9558 100644 --- a/src/mip/platform/tcp_connection.hpp +++ b/src/mip/platform/tcp_connection.hpp @@ -6,27 +6,52 @@ #include - -extern mip::Timestamp getCurrentTimestamp(); - namespace mip { namespace platform { +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_platform +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief Can be used on Windows, OSX, or linux to communicate with a MIP device over TCP +/// class TcpConnection : public mip::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, size_t* length_out, mip::Timestamp* timestamp) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) final; bool sendToDevice(const uint8_t* data, size_t length) final; + bool isConnected() const; + bool connect(); + bool disconnect(); + + void connectionInfo(std::string &host_name, uint32_t &port) const + { + host_name = mHostname; + port = mPort; + }; + private: tcp_socket mSocket; + std::string mHostname; + uint16_t mPort = 0; + +public: + const char* interfaceName() const override { return mHostname.c_str(); } + uint32_t parameter() const override { return mPort; } }; +///@} +//////////////////////////////////////////////////////////////////////////////// + }; // namespace platform }; // namespace mip \ No newline at end of file diff --git a/src/mip/utils/serial_port.c b/src/mip/utils/serial_port.c index 37c339ccb..bffa9a829 100644 --- a/src/mip/utils/serial_port.c +++ b/src/mip/utils/serial_port.c @@ -1,9 +1,22 @@ +#include "mip/mip_logging.h" + #include "serial_port.h" +#if defined WIN32 +#include +#include +#elif defined __APPLE__ +#include +#endif + + #define COM_PORT_BUFFER_SIZE 0x200 #ifndef WIN32 //Unix only + +#define INVALID_HANDLE_VALUE -1 + speed_t baud_rate_to_speed(int baud_rate) { switch(baud_rate) @@ -52,30 +65,74 @@ speed_t baud_rate_to_speed(int baud_rate) } #endif +void serial_port_init(serial_port *port) +{ + port->handle = INVALID_HANDLE_VALUE; +} + 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); #ifdef WIN32 BOOL ready; DCB dcb; + // Prepend '\\.\' to the com port if not already present. + bool added_prefix = false; + const char* tmp_port_str = port_str; + size_t port_str_len = strlen(port_str); + + // Only prepend if port_str is of the form 'COMx' + if(port_str_len >= 4 && toupper(port_str[0]) == 'C' && toupper(port_str[1]) == 'O' && toupper(port_str[2]) == 'M' && isdigit(port_str[3])) + { + char* tmp = (char*)malloc(port_str_len + 4 + 1); + if (!tmp) + return false; + + tmp[0] = '\\'; + tmp[1] = '\\'; + tmp[2] = '.'; + tmp[3] = '\\'; + memcpy(&tmp[4], port_str, port_str_len+1); + + added_prefix = true; + tmp_port_str = tmp; + } + //Connect to the provided com port - port->handle = CreateFile(port_str, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL); - + port->handle = CreateFile(tmp_port_str, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL); + + // Ensure that the free() call in the following 'if' block doesn't clobber an error value + DWORD last_error = GetLastError(); + + // If the port string was modified + if (added_prefix) + { + free(tmp_port_str); + tmp_port_str = NULL; + } + //Check for an invalid handle if(port->handle == INVALID_HANDLE_VALUE) { - printf( "\nError: Unable to open com port (%d)\n", GetLastError( ) ); + MIP_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); + CloseHandle(port->handle); + port->handle = INVALID_HANDLE_VALUE; return false; - + } + //Set the timeouts + COMMTIMEOUTS timeouts; GetCommTimeouts(port->handle, &timeouts); @@ -90,15 +147,17 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) //Setup the com port parameters ready = GetCommState(port->handle, &dcb); - + //Close the serial port, mutex, and exit if(!ready) { + MIP_LOG_ERROR("Unable to get com state\n"); CloseHandle(port->handle); + port->handle = INVALID_HANDLE_VALUE; return false; } - dcb.BaudRate = baudrate; //Baudrate is typically 115200 + dcb.BaudRate = baudrate; //Baudrate is typically 115200 dcb.ByteSize = 8; //Charsize is 8, default for MicroStrain dcb.Parity = NOPARITY; //Parity is none, default for MicroStrain dcb.StopBits = ONESTOPBIT; //Stopbits is 1, default for MicroStrain @@ -106,30 +165,55 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) dcb.fDtrControl = DTR_CONTROL_ENABLE; ready = SetCommState(port->handle, &dcb); - + //Close the serial port and exit if(!ready) { + MIP_LOG_ERROR("Unable to set com state\n"); CloseHandle(port->handle); + port->handle = INVALID_HANDLE_VALUE; return false; } - + #else //Linux +#ifdef __APPLE__ + port->handle = open(port_str, O_RDWR | O_NOCTTY | O_NDELAY); +#else port->handle = open(port_str, O_RDWR | O_NOCTTY | O_SYNC); +#endif + if (port->handle < 0) { + MIP_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)); + } + // 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)); + close(port->handle); + port->handle = -1; return false; + } +#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)); + close(port->handle); + port->handle = -1; return false; + } +#endif // Other serial settings to match MSCL serial_port_settings.c_cflag |= (tcflag_t)(CLOCAL | CREAD); @@ -143,45 +227,59 @@ 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)); + close(port->handle); + port->handle = -1; + return false; + } + + +#ifdef __APPLE__ + 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)); + close(port->handle); + port->handle = -1; return false; - + } +#endif + // Flush any waiting data tcflush(port->handle, TCIOFLUSH); #endif //Success - port->is_open = true; return true; } bool serial_port_close(serial_port *port) { - if(!port->is_open) + if(!serial_port_is_open(port)) return false; #ifdef WIN32 //Windows - //Close the serial port CloseHandle(port->handle); - -#else //Linux +#else //Linux & Mac close(port->handle); #endif + port->handle = INVALID_HANDLE_VALUE; - port->is_open = false; return true; } 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(!port->is_open) + if(!serial_port_is_open(port)) return false; - + #ifdef WIN32 //Windows DWORD local_bytes_written; @@ -189,7 +287,7 @@ bool serial_port_write(serial_port *port, const void *buffer, size_t num_bytes, if(WriteFile(port->handle, buffer, num_bytes, &local_bytes_written, NULL)) { *bytes_written = local_bytes_written; - + if(*bytes_written == num_bytes) return true; } @@ -199,23 +297,45 @@ 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)); + #endif return false; } -bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, size_t *bytes_read) +bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wait_time, size_t *bytes_read) { - //Set the bytes read to zero *bytes_read = 0; //Check for a valid port handle - if(!port->is_open) + if(!serial_port_is_open(port)) return false; - + #ifdef WIN32 //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); + serial_port_close(port); + return false; + } + + if( wait_time <= 0 ) + { + if(bytes_available == 0 ) + return true; + } + + //Don't let windows block on the read + if(bytes_available < num_bytes) + num_bytes = (bytes_available > 0) ? bytes_available : 1; + DWORD local_bytes_read; //Call the windows read function @@ -226,17 +346,38 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, size_t #else //Linux // Poll the device before attempting to read any data, so we will only block for 10ms if there is no data available struct pollfd poll_fd = { .fd = port->handle, .events = POLLIN }; - int poll_status = poll(&poll_fd, 1, 10); + int poll_status = poll(&poll_fd, 1, wait_time); // Keep reading and polling while there is still data available - if (poll_status > 0 && poll_fd.revents & POLLIN) + if (poll_status == -1) + { + MIP_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"); + serial_port_close(port); + return false; + } + else if (poll_fd.revents & POLLERR || poll_fd.revents & POLLNVAL) + { + MIP_LOG_ERROR("Poll encountered error\n"); + return false; + } + else if (poll_status > 0 && poll_fd.revents & POLLIN) { ssize_t local_bytes_read = read(port->handle, buffer, num_bytes); if(local_bytes_read == (ssize_t)-1 && errno != EAGAIN) + { + MIP_LOG_ERROR("Failed to read serial data (%d): %s\n", errno, strerror(errno)); return false; + } if(local_bytes_read >= 0) + { *bytes_read = local_bytes_read; + } } #endif @@ -246,20 +387,25 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, size_t uint32_t serial_port_read_count(serial_port *port) { +#ifdef WIN32 //Windows + // Clear the last error, if any + SetLastError(0); +#endif + //Check for a valid port handle - if(!port->is_open) + if(!serial_port_is_open(port)) return 0; - + #ifdef WIN32 //Windows COMSTAT com_status; DWORD errors; - + //This function gets the current com status if(ClearCommError(port->handle, &errors, &com_status)) { return com_status.cbInQue; } - + #else //Linux int bytes_available; ioctl(port->handle, FIONREAD, &bytes_available); @@ -270,7 +416,11 @@ uint32_t serial_port_read_count(serial_port *port) return 0; } -bool serial_port_is_open(serial_port *port) +bool serial_port_is_open(const serial_port *port) { - return port->is_open; +#ifdef WIN32 + return port->handle != INVALID_HANDLE_VALUE; +#else + return port->handle >= 0; +#endif } diff --git a/src/mip/utils/serial_port.h b/src/mip/utils/serial_port.h index a19cf4135..a56b0c259 100644 --- a/src/mip/utils/serial_port.h +++ b/src/mip/utils/serial_port.h @@ -1,11 +1,16 @@ #pragma once #ifdef WIN32 +#ifndef WIN32_LEAN_AND_MEAN +#define WIN32_LEAN_AND_MEAN +#endif + #include #else #include #include #include +#include #include #include #include @@ -21,7 +26,7 @@ extern "C" { #endif //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_extras Extra utilities +///@addtogroup mip_platform Platform specific utilities /// ///@{ @@ -34,7 +39,6 @@ extern "C" { typedef struct serial_port { - bool is_open; #ifdef WIN32 //Windows HANDLE handle; #else //Linux @@ -42,13 +46,13 @@ typedef struct serial_port #endif } serial_port; - +void serial_port_init(serial_port *port); bool serial_port_open(serial_port *port, const char *port_str, int baudrate); 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); -bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, size_t *bytes_read); +bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wait_time, size_t *bytes_read); uint32_t serial_port_read_count(serial_port *port); -bool serial_port_is_open(serial_port *port); +bool serial_port_is_open(const serial_port *port); ///@} ///@} diff --git a/src/mip/utils/serialization.c b/src/mip/utils/serialization.c index 4bb897a13..96cef9bce 100644 --- a/src/mip/utils/serialization.c +++ b/src/mip/utils/serialization.c @@ -1,225 +1,278 @@ - -#include "serialization.h" -#include "../mip_field.h" - -#include - -#ifdef __cplusplus -namespace mip { -#endif - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Initialize a serialization struct for insertion into a buffer. -/// -///@param serializer -///@param buffer -/// Buffer into which data will be written. Can be NULL if buffer_size==0. -///@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) -{ - serializer->_buffer = buffer; - serializer->_buffer_size = buffer_size; - serializer->_offset = 0; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Initialize a serialization struct for extract from a buffer. -/// -///@param serializer -///@param buffer -/// A pointer from which data will be read. -///@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) -{ - serializer->_buffer = (uint8_t*)buffer; - serializer->_buffer_size = buffer_size; - serializer->_offset = 0; -} - -//////////////////////////////////////////////////////////////////////////////// -///@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. -/// -///@param serializer -/// -///@returns The buffer size. -/// -size_t mip_serializer_capacity(const mip_serializer* serializer) -{ - return serializer->_buffer_size; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines the length of the data in the buffer. -/// -///@param 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 -/// the data. -/// -size_t mip_serializer_length(const mip_serializer* serializer) -{ - return serializer->_offset; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines the difference between the length and buffer size. -/// -///@param serializer -/// -/// For insertion, returns how many unwritten bytes remain in the buffer. -/// For extraction, returns how many bytes have not been read. -/// -///@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. -/// -remaining_count mip_serializer_remaining(const mip_serializer* serializer) -{ - return mip_serializer_capacity(serializer) - mip_serializer_length(serializer); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the data read/written is less than the buffer size. -/// -/// If the application attempts to read or write beyond the end of the buffer -/// (as defined by the buffer_size passed to the init function), the read or -/// write will be a no-op but the offset will still be advanced. This allows -/// the condition to be detected. -/// -///@param serializer -/// -///@returns true if mip_serializer_remaining() >= 0. -/// -bool mip_serializer_is_ok(const mip_serializer* serializer) -{ - return mip_serializer_length(serializer) <= mip_serializer_capacity(serializer); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Determines if the number of remaining bytes is 0. -/// -/// Use this to determine if the entire buffer has been extracted. It is not -/// particularly useful for insertion. -/// -///@param serializer -/// -///@returns true if mip_serializer_remaining() == 0. -/// -bool mip_serializer_is_complete(const mip_serializer* serializer) -{ - return serializer->_offset == serializer->_buffer_size; -} - - -static void pack(uint8_t* buffer, const void* value, size_t size) -{ - for(size_t i=0; i_offset + sizeof(type); \ - if( offset <= serializer->_buffer_size ) \ - pack(&serializer->_buffer[serializer->_offset], &value, sizeof(type)); \ - serializer->_offset = offset; \ -} - -INSERT_MACRO(bool, bool ) -INSERT_MACRO(char, char ) -INSERT_MACRO(u8, uint8_t ) -INSERT_MACRO(u16, uint16_t) -INSERT_MACRO(u32, uint32_t) -INSERT_MACRO(u64, uint64_t) -INSERT_MACRO(s8, int8_t ) -INSERT_MACRO(s16, int16_t ) -INSERT_MACRO(s32, int32_t ) -INSERT_MACRO(s64, int64_t ) -INSERT_MACRO(float, float ) -INSERT_MACRO(double, double ) - - - -static void unpack(const uint8_t* buffer, void* value, size_t size) -{ - for(size_t i=0; i_offset + sizeof(type); \ - if( offset <= serializer->_buffer_size ) \ - unpack(&serializer->_buffer[serializer->_offset], value, sizeof(type)); \ - serializer->_offset = offset; \ -} - -EXTRACT_MACRO(bool, bool ) -EXTRACT_MACRO(char, char ) -EXTRACT_MACRO(u8, uint8_t ) -EXTRACT_MACRO(u16, uint16_t) -EXTRACT_MACRO(u32, uint32_t) -EXTRACT_MACRO(u64, uint64_t) -EXTRACT_MACRO(s8, int8_t ) -EXTRACT_MACRO(s16, int16_t ) -EXTRACT_MACRO(s32, int32_t ) -EXTRACT_MACRO(s64, int64_t ) -EXTRACT_MACRO(float, float ) -EXTRACT_MACRO(double, double ) - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Similar to 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. -/// -///@param serializer -///@param count_out -/// 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. -/// -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); - if( *count_out > max_count ) - { - // This is an error condition which can occur if the device sends - // more array entries than the receiving structure expected. - // This does not imply any sort of protocol violation, only that - // the receiving array was not large enough. - // Either way, deserialization cannot continue because the following - // array extraction would leave some elements in the input buffer. - *count_out = 0; - serializer->_offset = SIZE_MAX; - } -} - -#ifdef __cplusplus -} // namespace mip -#endif + +#include "serialization.h" +#include "../mip_field.h" +#include "../mip_packet.h" +#include "../mip_offsets.h" + +#include +#include + +#ifdef __cplusplus +namespace mip { +#endif + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initialize a serialization struct for insertion into a buffer. +/// +///@param serializer +///@param buffer +/// Buffer into which data will be written. Can be NULL if buffer_size==0. +///@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) +{ + serializer->_buffer = buffer; + serializer->_buffer_size = buffer_size; + serializer->_offset = 0; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initialize a serialization struct for extraction from a buffer. +/// +///@param serializer +///@param buffer +/// A pointer from which data will be read. +///@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) +{ + 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( mip_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. +/// +///@param serializer +/// +///@returns The buffer size. +/// +size_t mip_serializer_capacity(const mip_serializer* serializer) +{ + return serializer->_buffer_size; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines the length of the data in the buffer. +/// +///@param 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 +/// the data. +/// +size_t mip_serializer_length(const mip_serializer* serializer) +{ + return serializer->_offset; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines the difference between the length and buffer size. +/// +///@param serializer +/// +/// For insertion, returns how many unwritten bytes remain in the buffer. +/// For extraction, returns how many bytes have not been read. +/// +///@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. +/// +int mip_serializer_remaining(const mip_serializer* serializer) +{ + return (int)(mip_serializer_capacity(serializer) - mip_serializer_length(serializer)); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the data read/written is less than the buffer size. +/// +/// If the application attempts to read or write beyond the end of the buffer +/// (as defined by the buffer_size passed to the init function), the read or +/// write will be a no-op but the offset will still be advanced. This allows +/// the condition to be detected. +/// +///@param serializer +/// +///@returns true if mip_serializer_remaining() >= 0. +/// +bool mip_serializer_is_ok(const mip_serializer* serializer) +{ + return mip_serializer_length(serializer) <= mip_serializer_capacity(serializer); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Determines if the number of remaining bytes is 0. +/// +/// Use this to determine if the entire buffer has been extracted. It is not +/// particularly useful for insertion. +/// +///@param serializer +/// +///@returns true if mip_serializer_remaining() == 0. +/// +bool mip_serializer_is_complete(const mip_serializer* serializer) +{ + return serializer->_offset == serializer->_buffer_size; +} + + +static void pack(uint8_t* buffer, const void* value, size_t size) +{ + for(size_t i=0; i_offset + sizeof(type); \ + if( offset <= serializer->_buffer_size ) \ + pack(&serializer->_buffer[serializer->_offset], &value, sizeof(type)); \ + serializer->_offset = offset; \ +} + +INSERT_MACRO(bool, bool ) +INSERT_MACRO(char, char ) +INSERT_MACRO(u8, uint8_t ) +INSERT_MACRO(u16, uint16_t) +INSERT_MACRO(u32, uint32_t) +INSERT_MACRO(u64, uint64_t) +INSERT_MACRO(s8, int8_t ) +INSERT_MACRO(s16, int16_t ) +INSERT_MACRO(s32, int32_t ) +INSERT_MACRO(s64, int64_t ) +INSERT_MACRO(float, float ) +INSERT_MACRO(double, double ) + + + +static void unpack(const uint8_t* buffer, void* value, size_t size) +{ + for(size_t i=0; i_offset + sizeof(type); \ + if( offset <= serializer->_buffer_size ) \ + unpack(&serializer->_buffer[serializer->_offset], value, sizeof(type)); \ + serializer->_offset = offset; \ +} + +EXTRACT_MACRO(bool, bool ) +EXTRACT_MACRO(char, char ) +EXTRACT_MACRO(u8, uint8_t ) +EXTRACT_MACRO(u16, uint16_t) +EXTRACT_MACRO(u32, uint32_t) +EXTRACT_MACRO(u64, uint64_t) +EXTRACT_MACRO(s8, int8_t ) +EXTRACT_MACRO(s16, int16_t ) +EXTRACT_MACRO(s32, int32_t ) +EXTRACT_MACRO(s64, int64_t ) +EXTRACT_MACRO(float, float ) +EXTRACT_MACRO(double, double ) + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Similar to 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. +/// +///@param serializer +///@param count_out +/// 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. +/// +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); + if( *count_out > max_count ) + { + // This is an error condition which can occur if the device sends + // more array entries than the receiving structure expected. + // This does not imply any sort of protocol violation, only that + // the receiving array was not large enough. + // Either way, deserialization cannot continue because the following + // array extraction would leave some elements in the input buffer. + *count_out = 0; + serializer->_offset = SIZE_MAX; + } +} + +#ifdef __cplusplus +} // namespace mip +#endif diff --git a/src/mip/utils/serialization.h b/src/mip/utils/serialization.h index 204dba1e4..d0b03f6b0 100644 --- a/src/mip/utils/serialization.h +++ b/src/mip/utils/serialization.h @@ -1,272 +1,282 @@ -#pragma once - -#include -#include - -#include "../mip_types.h" -#include "../mip_field.h" - -//////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_serialization MIP Serialization -/// -///@brief Serialization Functions for reading and writing to byte buffers. -///@{ -///@defgroup mip_serialization_c MIP Serialization [C] -///@defgroup mip_serialization_cpp MIP Serialization [CPP] -///@} - -#ifdef __cplusplus -#include - -namespace mip { -namespace C { -extern "C" { -#endif // __cplusplus - - -//////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_serialization_c -/// -///@brief (De)serialization in C. -/// -///@{ - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Structure used for serialization. -/// -///@note This should be considered an "opaque" structure; its members should be -/// considered an internal implementation detail. Avoid accessing them directly -/// as they are subject to change in future versions of this software. -/// -/// -typedef struct mip_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; - -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_from_field(mip_serializer* serializer, const mip_field* field); - -size_t mip_serializer_capacity(const mip_serializer* serializer); -size_t mip_serializer_length(const mip_serializer* serializer); -remaining_count mip_serializer_remaining(const mip_serializer* serializer); - -bool mip_serializer_is_ok(const mip_serializer* serializer); -bool mip_serializer_is_complete(const mip_serializer* serializer); - - -void insert_bool(mip_serializer* serializer, bool value); -void insert_char(mip_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 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 insert_float (mip_serializer* serializer, float value); -void insert_double(mip_serializer* serializer, double value); - - -void extract_bool(mip_serializer* serializer, bool* value); -void extract_char(mip_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 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 extract_float (mip_serializer* serializer, float* value); -void extract_double(mip_serializer* serializer, double* value); - -void extract_count(mip_serializer* serializer, uint8_t* count_out, uint8_t max_count); - -///@} -//////////////////////////////////////////////////////////////////////////////// - -#ifdef __cplusplus -} // extern "C" -} // namespace C - -//////////////////////////////////////////////////////////////////////////////// -///@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(Serializer& serializer, Type value); -/// voie mip::extract(Serializer& 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 Serializer 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 Serializer : public C::mip_serializer -{ -public: - 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; } - - size_t capacity() const { return C::mip_serializer_capacity(this); } - size_t length() const { return C::mip_serializer_length(this); } - RemainingCount remaining() const { return C::mip_serializer_remaining(this); } - - bool isOk() const { return C::mip_serializer_is_ok(this); } - bool isComplete() const { return C::mip_serializer_is_complete(this); } - - operator const void*() const { return isOk() ? this : nullptr; } - bool operator!() const { return !isOk(); } -}; - - - -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); } - -//////////////////////////////////////////////////////////////////////////////// -///@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(Serializer& 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. -/// -///@returns true if sufficient space was available, false otherwise. -/// -template -bool insert(const T& value, uint8_t* buffer, size_t bufferSize) -{ - Serializer serializer(buffer, bufferSize); - insert(serializer, value); - 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); } - -//////////////////////////////////////////////////////////////////////////////// -///@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(Serializer& 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) -{ - Serializer serializer(buffer, bufferSize, offset); - extract(serializer, value_out); - return exact_size ? serializer.isComplete() : serializer.isOk(); -} - -///@} -///@} -//////////////////////////////////////////////////////////////////////////////// - -} // namespace mip -#endif // __cplusplus - +#pragma once + +#include +#include + +#include "../mip_field.h" +#include "../mip_packet.h" +#include "../mip_types.h" + +//////////////////////////////////////////////////////////////////////////////// +///@defgroup mip_serialization MIP Serialization +/// +///@brief Serialization Functions for reading and writing to byte buffers. +///@{ +///@defgroup mip_serialization_c MIP Serialization [C] +///@defgroup mip_serialization_cpp MIP Serialization [CPP] +///@} + +#ifdef __cplusplus +#include + +namespace mip { +namespace C { +extern "C" { +#endif // __cplusplus + + + +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_serialization_c +/// +///@brief (De)serialization in C. +/// +///@{ + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Structure used for serialization. +/// +///@note This should be considered an "opaque" structure; its members should be +/// considered an internal implementation detail. Avoid accessing them directly +/// as they are subject to change in future versions of this software. +/// +/// +typedef struct mip_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; + +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); + +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); + +bool mip_serializer_is_ok(const mip_serializer* serializer); +bool mip_serializer_is_complete(const mip_serializer* serializer); + + +void insert_bool(mip_serializer* serializer, bool value); +void insert_char(mip_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 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 insert_float (mip_serializer* serializer, float value); +void insert_double(mip_serializer* serializer, double value); + + +void extract_bool(mip_serializer* serializer, bool* value); +void extract_char(mip_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 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 extract_float (mip_serializer* serializer, float* value); +void extract_double(mip_serializer* serializer, double* value); + +void extract_count(mip_serializer* serializer, uint8_t* count_out, uint8_t max_count); + +///@} +//////////////////////////////////////////////////////////////////////////////// + +#ifdef __cplusplus +} // extern "C" +} // namespace C + +//////////////////////////////////////////////////////////////////////////////// +///@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(Serializer& serializer, Type value); +/// voie mip::extract(Serializer& 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 Serializer 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 Serializer : public C::mip_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; } + + 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); } + + bool isOk() const { return C::mip_serializer_is_ok(this); } + bool isComplete() const { return C::mip_serializer_is_complete(this); } + + operator const void*() const { return isOk() ? this : nullptr; } + bool operator!() const { return !isOk(); } +}; + + + +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); } + +//////////////////////////////////////////////////////////////////////////////// +///@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(Serializer& 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) +{ + Serializer serializer(buffer, bufferSize, offset); + insert(serializer, value); + 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); } + +//////////////////////////////////////////////////////////////////////////////// +///@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(Serializer& 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) +{ + Serializer serializer(buffer, bufferSize, offset); + extract(serializer, value_out); + return exact_size ? serializer.isComplete() : serializer.isOk(); +} + +///@} +///@} +//////////////////////////////////////////////////////////////////////////////// + +} // namespace mip +#endif // __cplusplus + //////////////////////////////////////////////////////////////////////////////// \ No newline at end of file diff --git a/src/mip/utils/tcp_socket.c b/src/mip/utils/tcp_socket.c index 16db78dd1..1e4d05734 100644 --- a/src/mip/utils/tcp_socket.c +++ b/src/mip/utils/tcp_socket.c @@ -1,22 +1,49 @@ #include "tcp_socket.h" -#ifdef WIN32 +#include "mip/mip_logging.h" + +#ifdef _WIN32 + +#include +#include + +static const int SEND_FLAGS = 0; + +#ifdef _MSC_VER +typedef int ssize_t; +#endif + #else + #include #include #include #include #include #include -#include + +static const int INVALID_SOCKET = -1; +static const int SEND_FLAGS = MSG_NOSIGNAL; + #endif -bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port, size_t timeout_ms) +#include + +void tcp_socket_init(tcp_socket* socket_ptr) { -#ifdef WIN32 - return false; // TODO: Windows -#else + socket_ptr->handle = INVALID_SOCKET; +} + +bool tcp_socket_is_open(const tcp_socket* socket_ptr) +{ + return socket_ptr->handle != INVALID_SOCKET; +} + +static bool tcp_socket_open_common(tcp_socket* socket_ptr, const char* hostname, uint16_t port, unsigned int timeout_ms) +{ + //assert(socket_ptr->handle == INVALID_SOCKET); + // https://man7.org/linux/man-pages/man3/getaddrinfo.3.html struct addrinfo hints, *info; memset(&hints, 0, sizeof(hints)); @@ -35,21 +62,32 @@ bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port for(struct addrinfo* addr=info; addr!=NULL; addr=addr->ai_next) { socket_ptr->handle = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); //socket(addr->ai_family, addr->ai_socktype, addr->ai_protocol); - if( socket_ptr->handle == -1 ) + if( socket_ptr->handle == INVALID_SOCKET ) continue; if( connect(socket_ptr->handle, addr->ai_addr, addr->ai_addrlen) == 0 ) break; +#ifdef WIN32 + closesocket(socket_ptr->handle); +#else close(socket_ptr->handle); - socket_ptr->handle = -1; +#endif + socket_ptr->handle = INVALID_SOCKET; } freeaddrinfo(info); - if( socket_ptr->handle == -1 ) + if( socket_ptr->handle == INVALID_SOCKET ) return false; +#ifdef WIN32 + if( setsockopt(socket_ptr->handle, SOL_SOCKET, SO_RCVTIMEO, (char*)&timeout_ms, sizeof(timeout_ms)) != 0 ) + return false; + + if( setsockopt(socket_ptr->handle, SOL_SOCKET, SO_SNDTIMEO, (char*)&timeout_ms, sizeof(timeout_ms)) != 0 ) + return false; +#else struct timeval timeout_option; timeout_option.tv_sec = timeout_ms / 1000; timeout_option.tv_usec = (timeout_ms % 1000) * 1000; @@ -59,57 +97,73 @@ bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port if( setsockopt(socket_ptr->handle, SOL_SOCKET, SO_SNDTIMEO, &timeout_option, sizeof(timeout_option)) != 0 ) return false; +#endif return true; -#endif } -bool tcp_socket_close(tcp_socket* socket_ptr) +bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port, unsigned int timeout_ms) { #ifdef WIN32 - return false; // TODO: Windows -#else - if( socket_ptr->handle != -1 ) + + // 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. + struct WSAData wsaData; + int result = WSAStartup(MAKEWORD(2,2), &wsaData); + if(result != 0) { - close(socket_ptr->handle); - socket_ptr->handle = -1; - return true; - } - else + MIP_LOG_ERROR("WSAStartup() failed: %d\n", result); return false; + } + #endif + + return tcp_socket_open_common(socket_ptr, hostname, port ,timeout_ms); } -bool tcp_socket_send(tcp_socket* socket_ptr, const void* buffer, size_t num_bytes, size_t* bytes_written) +bool tcp_socket_close(tcp_socket* socket_ptr) { + if( socket_ptr->handle == INVALID_SOCKET ) + return false; + #ifdef WIN32 - return false; // TODO: Windows + closesocket(socket_ptr->handle); + WSACleanup(); // See tcp_socket_open #else + close(socket_ptr->handle); +#endif + + socket_ptr->handle = INVALID_SOCKET; + return true; +} + +bool tcp_socket_send(tcp_socket* socket_ptr, const void* buffer, size_t num_bytes, size_t* bytes_written) +{ for(*bytes_written = 0; *bytes_written < num_bytes; ) { - ssize_t sent = send(socket_ptr->handle, buffer, num_bytes, MSG_NOSIGNAL); + ssize_t sent = send(socket_ptr->handle, buffer, num_bytes, SEND_FLAGS); if(sent < 0) return false; *bytes_written += sent; } return true; -#endif } bool tcp_socket_recv(tcp_socket* socket_ptr, void* buffer, size_t num_bytes, size_t* bytes_read) { -#ifdef WIN32 - return false; // TODO: Windows -#else - ssize_t local_bytes_read = recv(socket_ptr->handle, buffer, num_bytes, MSG_NOSIGNAL); + ssize_t local_bytes_read = recv(socket_ptr->handle, buffer, num_bytes, SEND_FLAGS); - if( local_bytes_read == -1 ) + if( local_bytes_read < 0 ) { +#ifdef WIN32 + return false; +#else if(errno != EAGAIN && errno != EWOULDBLOCK) return false; else return true; +#endif } // Throw an error if the connection has been closed by the other side. else if( local_bytes_read == 0 ) @@ -117,5 +171,4 @@ bool tcp_socket_recv(tcp_socket* socket_ptr, void* buffer, size_t num_bytes, siz *bytes_read = local_bytes_read; return true; -#endif } diff --git a/src/mip/utils/tcp_socket.h b/src/mip/utils/tcp_socket.h index 38a582384..62827286c 100644 --- a/src/mip/utils/tcp_socket.h +++ b/src/mip/utils/tcp_socket.h @@ -1,5 +1,15 @@ #pragma once +#ifdef WIN32 + +#ifndef WIN32_LEAN_AND_MEAN +#define WIN32_LEAN_AND_MEAN +#endif + +#include + +#endif + #include #include #include @@ -9,7 +19,7 @@ extern "C" { #endif //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_extras +///@addtogroup mip_platform /// ///@{ @@ -22,11 +32,18 @@ extern "C" { typedef struct tcp_socket { +#ifdef WIN32 + SOCKET handle; +#else int handle; +#endif } tcp_socket; -bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port, size_t timeout_ms); + +void tcp_socket_init(tcp_socket* socket_ptr); +bool tcp_socket_is_open(const tcp_socket* socket_ptr); +bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port, unsigned int timeout_ms); bool tcp_socket_close(tcp_socket* socket_ptr); bool tcp_socket_send(tcp_socket* socket_ptr, const void* buffer, size_t num_bytes, size_t* bytes_written); bool tcp_socket_recv(tcp_socket* socket_ptr, void* buffer, size_t num_bytes, size_t* bytes_read); diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 226e10aaa..14d2eb56a 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -20,6 +20,7 @@ add_mip_test(TestMipParsing "${TEST_DIR}/mip/test_mip_parser.c" TestMipPa 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) if(WITH_SERIAL) add_executable(TestSerial "${TEST_DIR}/test_serial.cpp") diff --git a/test/mip/mip_parser_performance.cpp b/test/mip/mip_parser_performance.cpp new file mode 100644 index 000000000..bb5e80a1a --- /dev/null +++ b/test/mip/mip_parser_performance.cpp @@ -0,0 +1,246 @@ + +#include "mip/mip.hpp" + +#include +#include +#include +#include + +#include + +const uint8_t PING_PACKET[] = {0x75, 0x65, 0x01, 0x02, 0x02, 0x01, 0xE0, 0xC6}; + +const uint8_t DATA_PACKET[] = { + 0x75,0x65,0x82,0xc1,0x0e,0xd3,0x40,0x8c,0x84,0xef,0x9d,0xb2,0x2d,0x0f,0x00,0x00, + 0x00,0x00,0x0a,0xd5,0x00,0x00,0x00,0xd4,0x7c,0x36,0x4c,0x40,0x10,0x05,0x7f,0xff, + 0xff,0xf8,0x7f,0xc0,0x00,0x00,0x7f,0xff,0xff,0xf8,0x00,0x01,0x10,0x06,0x7f,0xc0, + 0x00,0x00,0x7f,0xc0,0x00,0x00,0x7f,0xc0,0x00,0x00,0x00,0x01,0x10,0x07,0x00,0x00, + 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x08,0x10,0x00,0x02, + 0x00,0x00,0x00,0x00,0x1c,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, + 0x10,0x02,0x7f,0xc0,0x00,0x00,0x7f,0xc0,0x00,0x00,0x7f,0xc0,0x00,0x00,0x00,0x00, + 0x1c,0x42,0x7f,0xf8,0x00,0x00,0x00,0x00,0x00,0x00,0x7f,0xf8,0x00,0x00,0x00,0x00, + 0x00,0x00,0x7f,0xf8,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x09,0x46,0x44,0x64, + 0x26,0x87,0x00,0x04,0x01,0x10,0x08,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00,0x00,0x10,0x09,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00,0x00,0x87,0x56, // 199 bytes +}; + +const char NMEA_SENTENCE[] = "$GPGGA,123456.7,1234.5678,N,1234.5678,W,1,5,1.2,12.345,M,12.345,M,*4F"; + + +struct Test +{ + const char* name = nullptr; + unsigned int num_iterations = 1; + size_t num_packets = 0; + std::vector data; + std::vector chunk_sizes; +}; + + +Test generate_pings() +{ + Test test; + + test.name = "Pings"; + test.num_packets = 200000; + test.num_iterations = 10; + test.chunk_sizes = {5, 8, 19}; + + test.data.resize(sizeof(PING_PACKET)*test.num_packets); + + for(unsigned int i=0; i(v) += 1; + return true; + }; + size_t num_pkts = 0; + mip::Parser parser(parse_buffer, sizeof(parse_buffer), callback, &num_pkts, MIPPARSER_DEFAULT_TIMEOUT_MS); + + + const size_t num_full_chunks = (chunk_size == 0) ? 1 : (test.data.size() / chunk_size); + std::vector chunk_times(num_full_chunks * test.num_iterations); + + assert(test.num_iterations > 0); + for(unsigned int i = 0; i < test.num_iterations; i++) + { + parser.reset(); + num_pkts = 0; + + const size_t buffer_size = (chunk_size > 0) ? chunk_size : test.data.size(); + const uint8_t *buffer = test.data.data(); + + for(size_t c = 0; c < num_full_chunks; c++) + { + auto start = std::chrono::steady_clock::now(); + dummy = true; // Hopefully prevent compiler/cpu from reordering clock and parse calls. + parser.parse(buffer, buffer_size, 0); + dummy = false; + auto stop = std::chrono::steady_clock::now(); + + std::chrono::duration duration = stop - start; + + chunk_times[i * num_full_chunks + c] = duration.count(); + buffer += chunk_size; + } + if(chunk_size > 0) + parser.parse(test.data.data() + num_full_chunks * chunk_size, test.data.size() - num_full_chunks * chunk_size, 0); + + if(num_pkts != test.num_packets) + fprintf(stderr, "Error: Got %zu packets but expected %zu!\n", num_pkts, test.num_packets); + } + + ChunkStats stats; + stats.chunk_size = chunk_size; + stats.num_calls = num_full_chunks; + stats.total_time = (float)std::accumulate(chunk_times.begin(), chunk_times.end(), 0.0) / test.num_iterations; // Accumulate with double precision! + stats.avg_time = stats.total_time / num_full_chunks; + stats.max_time = *std::max_element(chunk_times.begin(), chunk_times.end()); + + std::sort(chunk_times.begin(), chunk_times.end()); + stats.med_time = chunk_times[chunk_times.size()/2]; + + return stats; +} + + +int main(int argc, const char* argv[]) +{ + std::initializer_list tests = { + generate_pings(), + generate_long_pkts(), + generate_interleaved() + }; + + std::initializer_list chunk_sizes = {5, 8, 19, 53, 127, 512, 1024, 8192}; + + std::vector stats(tests.size() * (chunk_sizes.size()+1)); + + size_t t = 0; + for(const Test& test : tests) + { + printf("Test %s...\n", test.name); + + size_t s = 0; + for(size_t chunk_size : chunk_sizes) + { + printf(" Chunk size %zu\n", chunk_size); + stats[t * (chunk_sizes.size()+1) + s] = chunked_test(test, chunk_size); + s++; + } + printf(" Chunk size oo\n"); + stats[t * (chunk_sizes.size()+1) + s] = chunked_test(test, test.data.size()); + + t++; + } + + std::printf("\n\n" + " Test Total Chunk Parse Mean Median Max Though Through \n" + " Name Bytes Size[B] Calls Time[us] Time[us] Time[us] [MB/s] [MPkt/s] \n" + "---------------------------------------------------------------------------------------------------------\n" + ); + + t=0; + for(const Test& test : tests) + { + size_t s=0; + for(size_t chunk_size : chunk_sizes) + { + const ChunkStats& stat = stats[t * (chunk_sizes.size()+1) + s]; + + std::printf("%16s %8zu %8zu %8zu %8.2f %8.2f %8.2f %8.2f %8.2f\n", + test.name, stat.chunk_size * stat.num_calls, chunk_size, stat.num_calls, + stat.avg_time*1e6f, stat.med_time*1e6f, stat.max_time*1e6f, + test.data.size() / stat.total_time / 1e6f, + test.num_packets / stat.total_time / 1e6f + ); + + s++; + } + const ChunkStats& stat = stats[t * (chunk_sizes.size()+1) + s]; + + std::printf("%16s %8zu infinite %8zu %8.2f %8.2f %8.2f %8.2f %8.2f\n", + test.name, stat.chunk_size * stat.num_calls, stat.num_calls, + stat.avg_time*1e6f, stat.med_time*1e6f, stat.max_time*1e6f, + test.data.size() / stat.total_time / 1e6f, + test.num_packets / stat.total_time / 1e6f + ); + + t++; + } + + return 0; +} diff --git a/test/mip/test_mip.cpp b/test/mip/test_mip.cpp index f00ce3287..84aeb0e40 100644 --- a/test/mip/test_mip.cpp +++ b/test/mip/test_mip.cpp @@ -9,7 +9,7 @@ using namespace mip; - +using namespace mip::C; uint8_t packetBuffer[PACKET_LENGTH_MAX]; uint8_t parseBuffer[1024]; @@ -23,7 +23,7 @@ int main(int argc, const char* argv[]) { srand(0); - auto callback = [](void*, const Packet* parsedPacket, Timestamp timestamp)->bool + auto callback = [](void*, const PacketRef* 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 10 ) diff --git a/test/mip/test_mip_fields.c b/test/mip/test_mip_fields.c index e33dcac32..156c7a4be 100644 --- a/test/mip/test_mip_fields.c +++ b/test/mip/test_mip_fields.c @@ -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_from_packet(&packet); mip_field_is_valid(&field); mip_field_next(&field)) + for(struct mip_field 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); diff --git a/test/mip/test_mip_parser.c b/test/mip/test_mip_parser.c index 1dfd37382..7636f5482 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, timestamp_type t) +bool handle_packet(void* p, const struct mip_packet* packet, mip_timestamp t) { (void)t; diff --git a/test/mip/test_mip_random.c b/test/mip/test_mip_random.c index 6449a40f3..26bf944ad 100644 --- a/test/mip/test_mip_random.c +++ b/test/mip/test_mip_random.c @@ -12,8 +12,8 @@ struct mip_parser parser; unsigned int num_errors = 0; unsigned int num_packets_parsed = 0; -size_t parsed_packet_length = 0; -timestamp_type parsed_packet_timestamp = 0; +size_t parsed_packet_length = 0; +mip_timestamp parsed_packet_timestamp = 0; void print_packet(FILE* out, const struct mip_packet* 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, timestamp_type timestamp) +bool handle_packet(void* p, const struct mip_packet* packet, mip_timestamp timestamp) { (void)p; @@ -71,7 +71,7 @@ int main(int argc, const char* argv[]) const uint8_t field_desc = (rand() % 255) + 1; // Random field descriptor. uint8_t* payload; - remaining_count available = mip_packet_alloc_field(&packet, field_desc, paylen, &payload); + int available = mip_packet_alloc_field(&packet, field_desc, paylen, &payload); if( available < 0 ) { @@ -96,19 +96,17 @@ int main(int argc, const char* argv[]) // Send this packet to the parser in small chunks. // - const unsigned int MAX_CHUNKS = 5; - const size_t packet_size = mip_packet_total_length(&packet); // Keep track of offsets and timestamps for debug purposes. - size_t offsets[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_HEADER_LENGTH] = {0}; - timestamp_type timestamps[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_HEADER_LENGTH] = {0}; - unsigned int c = 0; + size_t offsets[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_HEADER_LENGTH] = {0}; + mip_timestamp timestamps[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_HEADER_LENGTH] = {0}; + unsigned int c = 0; - const timestamp_type start_time = rand(); - timestamp_type timestamp = start_time; - size_t sent = 0; + const mip_timestamp start_time = rand(); + mip_timestamp timestamp = start_time; + size_t sent = 0; // Send all but the last chunk. while( sent < (packet_size-MIP_PACKET_LENGTH_MIN) ) @@ -166,13 +164,13 @@ int main(int argc, const char* argv[]) { num_errors++; error = true; - fprintf(stderr, "Parsed packet has wrong timestamp %d\n", parsed_packet_timestamp); + fprintf(stderr, "Parsed packet has wrong timestamp %ld\n", parsed_packet_timestamp); } last_parsed = num_packets_parsed; if( error ) { - fprintf(stderr, " packet_size=%ld, last_count=%ld, extra=%ld, start_time=%d\n", packet_size, count, extra, start_time); + fprintf(stderr, " packet_size=%ld, last_count=%ld, extra=%ld, start_time=%ld\n", packet_size, count, extra, start_time); fprintf(stderr, " Sent chunks:"); for(unsigned int d=0; d